├── README.md ├── actionlib_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── cmake │ ├── actionbuild.cmake │ └── actionlib_msgs-extras.cmake.em ├── msg │ ├── GoalID.msg │ ├── GoalStatus.msg │ └── GoalStatusArray.msg ├── package.xml └── scripts │ └── genaction.py ├── common_msgs ├── CHANGELOG.rst ├── CMakeLists.txt └── package.xml ├── diagnostic_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── mainpage.dox ├── msg │ ├── DiagnosticArray.msg │ ├── DiagnosticStatus.msg │ └── KeyValue.msg ├── package.xml └── srv │ ├── AddDiagnostics.srv │ └── SelfTest.srv ├── geometry_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── mainpage.dox ├── msg │ ├── Accel.msg │ ├── AccelStamped.msg │ ├── AccelWithCovariance.msg │ ├── AccelWithCovarianceStamped.msg │ ├── Inertia.msg │ ├── InertiaStamped.msg │ ├── Point.msg │ ├── Point32.msg │ ├── PointStamped.msg │ ├── Polygon.msg │ ├── PolygonStamped.msg │ ├── Pose.msg │ ├── Pose2D.msg │ ├── PoseArray.msg │ ├── PoseStamped.msg │ ├── PoseWithCovariance.msg │ ├── PoseWithCovarianceStamped.msg │ ├── Quaternion.msg │ ├── QuaternionStamped.msg │ ├── Transform.msg │ ├── TransformStamped.msg │ ├── Twist.msg │ ├── TwistStamped.msg │ ├── TwistWithCovariance.msg │ ├── TwistWithCovarianceStamped.msg │ ├── Vector3.msg │ ├── Vector3Stamped.msg │ ├── Wrench.msg │ └── WrenchStamped.msg └── package.xml ├── nav_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── action │ └── GetMap.action ├── msg │ ├── GridCells.msg │ ├── MapMetaData.msg │ ├── OccupancyGrid.msg │ ├── Odometry.msg │ └── Path.msg ├── package.xml └── srv │ ├── GetMap.srv │ ├── GetPlan.srv │ ├── LoadMap.srv │ └── SetMap.srv ├── sensor_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── include │ └── sensor_msgs │ │ ├── distortion_models.h │ │ ├── fill_image.h │ │ ├── image_encodings.h │ │ ├── impl │ │ └── point_cloud2_iterator.h │ │ ├── point_cloud2_iterator.h │ │ ├── point_cloud_conversion.h │ │ └── point_field_conversion.h ├── mainpage.dox ├── migration_rules │ └── sensor_msgs.bmr ├── msg │ ├── BatteryState.msg │ ├── CameraInfo.msg │ ├── ChannelFloat32.msg │ ├── CompressedImage.msg │ ├── FluidPressure.msg │ ├── Illuminance.msg │ ├── Image.msg │ ├── Imu.msg │ ├── JointState.msg │ ├── Joy.msg │ ├── JoyFeedback.msg │ ├── JoyFeedbackArray.msg │ ├── LaserEcho.msg │ ├── LaserScan.msg │ ├── MagneticField.msg │ ├── MultiDOFJointState.msg │ ├── MultiEchoLaserScan.msg │ ├── NavSatFix.msg │ ├── NavSatStatus.msg │ ├── PointCloud.msg │ ├── PointCloud2.msg │ ├── PointField.msg │ ├── Range.msg │ ├── RegionOfInterest.msg │ ├── RelativeHumidity.msg │ ├── Temperature.msg │ └── TimeReference.msg ├── package.xml ├── setup.py ├── src │ └── sensor_msgs │ │ ├── __init__.py │ │ └── point_cloud2.py ├── srv │ └── SetCameraInfo.srv └── test │ ├── CMakeLists.txt │ ├── main.cpp │ └── test_image_encodings.cpp ├── shape_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── msg │ ├── Mesh.msg │ ├── MeshTriangle.msg │ ├── Plane.msg │ └── SolidPrimitive.msg └── package.xml ├── stereo_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── mainpage.dox ├── msg │ └── DisparityImage.msg └── package.xml ├── trajectory_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── msg │ ├── JointTrajectory.msg │ ├── JointTrajectoryPoint.msg │ ├── MultiDOFJointTrajectory.msg │ └── MultiDOFJointTrajectoryPoint.msg ├── package.xml └── rules │ └── JointTrajectoryPoint_Groovy2Hydro_08.10.2013.bmr └── visualization_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── mainpage.dox ├── msg ├── ImageMarker.msg ├── InteractiveMarker.msg ├── InteractiveMarkerControl.msg ├── InteractiveMarkerFeedback.msg ├── InteractiveMarkerInit.msg ├── InteractiveMarkerPose.msg ├── InteractiveMarkerUpdate.msg ├── Marker.msg ├── MarkerArray.msg └── MenuEntry.msg └── package.xml /README.md: -------------------------------------------------------------------------------- 1 | # Archived - ROS 1 End-of-life 2 | 3 | This repository contains ROS 1 packages. 4 | The last supported ROS 1 release, ROS Noetic, [officially reached end of life on May 31st, 2025](https://bit.ly/NoeticEOL). 5 | 6 | -------------------------------------------------------------------------------- /actionlib_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package actionlib_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.13.2 (2025-04-25) 6 | ------------------- 7 | 8 | 1.13.1 (2021-01-11) 9 | ------------------- 10 | * Update package maintainers (`#168 `_) 11 | * Contributors: Michel Hidalgo 12 | 13 | 1.13.0 (2020-05-21) 14 | ------------------- 15 | * Bump CMake version to avoid CMP0048 warning (`#158 `_) 16 | * Contributors: Shane Loretz 17 | 18 | 1.12.7 (2018-11-06) 19 | ------------------- 20 | 21 | 22 | 1.12.6 (2018-05-03) 23 | ------------------- 24 | 25 | 1.12.5 (2016-09-30) 26 | ------------------- 27 | * Fix spelling mistakes 28 | * Contributors: trorornmn 29 | 30 | 1.12.4 (2016-02-22) 31 | ------------------- 32 | 33 | 1.12.3 (2015-04-20) 34 | ------------------- 35 | 36 | 1.12.2 (2015-03-21) 37 | ------------------- 38 | 39 | 1.12.1 (2015-03-17) 40 | ------------------- 41 | * updating outdated urls. fixes `#52 `_. 42 | * Contributors: Tully Foote 43 | 44 | 1.12.0 (2014-12-29) 45 | ------------------- 46 | 47 | 1.11.6 (2014-11-04) 48 | ------------------- 49 | 50 | 1.11.5 (2014-10-27) 51 | ------------------- 52 | 53 | 1.11.4 (2014-06-19) 54 | ------------------- 55 | 56 | 1.11.3 (2014-05-07) 57 | ------------------- 58 | * Export architecture_independent flag in package.xml 59 | * Contributors: Scott K Logan 60 | 61 | 1.11.2 (2014-04-24) 62 | ------------------- 63 | 64 | 1.11.1 (2014-04-16) 65 | ------------------- 66 | 67 | 1.11.0 (2014-03-04) 68 | ------------------- 69 | 70 | 1.10.6 (2014-02-27) 71 | ------------------- 72 | * fix actionlib_msgs for dry 73 | * use catkin_install_python() to install Python scripts `#29 `_ 74 | * Contributors: Dirk Thomas 75 | 76 | 1.10.5 (2014-02-25) 77 | ------------------- 78 | * removing usage of catkin function not guaranteed available fixes `#30 `_ 79 | * Contributors: Tully Foote 80 | 81 | 1.10.4 (2014-02-18) 82 | ------------------- 83 | * remove catkin usage from CMake extra file (fix `#27 `_) 84 | * Contributors: Dirk Thomas 85 | 86 | 1.10.3 (2014-01-07) 87 | ------------------- 88 | * python 3 compatibility 89 | * prefix invocation of python script with PYTHON_EXECUTABLE (`ros/genpy#23 `_) 90 | * make generated cmake relocatable 91 | 92 | 1.10.2 (2013-08-19) 93 | ------------------- 94 | 95 | 1.10.1 (2013-08-16) 96 | ------------------- 97 | 98 | 1.10.0 (2013-07-13) 99 | ------------------- 100 | 101 | 1.9.16 (2013-05-21) 102 | ------------------- 103 | * update email in package.xml 104 | 105 | 1.9.15 (2013-03-08) 106 | ------------------- 107 | * fix handling spaces in folder names (`ros/catkin#375 `_) 108 | 109 | 1.9.14 (2013-01-19) 110 | ------------------- 111 | * fix bug using ARGV in list(FIND) directly (`ros/genmsg#18 `_) 112 | 113 | 1.9.13 (2013-01-13) 114 | ------------------- 115 | 116 | 1.9.12 (2013-01-02) 117 | ------------------- 118 | 119 | 1.9.11 (2012-12-17) 120 | ------------------- 121 | * add message_generation as a run dep for downstream 122 | * modified dep type of catkin 123 | 124 | 1.9.10 (2012-12-13) 125 | ------------------- 126 | * add missing downstream depend 127 | * switched from langs to message_* packages 128 | 129 | 1.9.9 (2012-11-22) 130 | ------------------ 131 | 132 | 1.9.8 (2012-11-14) 133 | ------------------ 134 | * add globbing for action files 135 | * updated variable to latest catkin 136 | * refactored extra file from 'in' to 'em' 137 | 138 | 1.9.7 (2012-10-30) 139 | ------------------ 140 | * fix catkin function order 141 | 142 | 1.9.6 (2012-10-18) 143 | ------------------ 144 | * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 145 | 146 | 1.9.5 (2012-09-28) 147 | ------------------ 148 | 149 | 1.9.4 (2012-09-27 18:06) 150 | ------------------------ 151 | 152 | 1.9.3 (2012-09-27 17:39) 153 | ------------------------ 154 | * cleanup 155 | * updated to latest catkin 156 | * fixed dependencies and more 157 | * updated to latest catkin: created package.xmls, updated CmakeLists.txt 158 | 159 | 1.9.2 (2012-09-05) 160 | ------------------ 161 | * updated pkg-config in manifest.xml 162 | * updated catkin variables 163 | 164 | 1.9.1 (2012-09-04) 165 | ------------------ 166 | * use install destination variables, removed manual installation of manifests 167 | 168 | 1.9.0 (2012-08-29) 169 | ------------------ 170 | * updated to current catkin 171 | 172 | 1.8.13 (2012-07-26 18:34:15 +0000) 173 | ---------------------------------- 174 | 175 | 1.8.8 (2012-06-12 22:36) 176 | ------------------------ 177 | * make find_package REQUIRED 178 | * removed obsolete catkin tag from manifest files 179 | * Fix up install-time finding of script, plus add a missing genmsg import 180 | * Convert legacy rosbuild support to use newer genaction.py script 181 | * Expose old actionlib_msgs interface to dry users. Dry actionlib builds and 182 | tests cleanly. 183 | * adding manifest exports 184 | * removed depend, added catkin 185 | * stripping depend and export tags from common_msgs manifests as msg dependencies are now declared in cmake and stack.yaml. Also removed bag migration exports 186 | * install a file that rosbuild users have hardcoded an include for 187 | * bye bye vestigial MSG_DIRS 188 | * rosbuild2 -> catkin 189 | * no include dir in actionlib_msgs 190 | * actionlib_msgs: getting rid of other build files 191 | * adios rosbuild2 in manifest.xml 192 | * catkin updates 193 | * catkin_project 194 | * catkin: only generate .msg files if .action file has changed 195 | * catkin: changed actionlib_msg to generate .msg files at cmake time 196 | * Integrate actionlib_msgs into catkin 197 | * rosbuild2 on windows tweaks (more) 198 | * rosbuild2 windows tweaks 199 | * url fix 200 | * removed extra slashes that caused trouble on OSX 201 | * rosbuild2 taking shape 202 | * rosbuild2 taking shape 203 | * removing all the extra exports 204 | * msg folder generation now parallel safe. `#4286 `_ 205 | * Fixing build dependency race condition. Trac `#4255 `_ 206 | * Added Ubuntu platform tags to manifest 207 | * Now using /usr/bin/env python. Trac `#3863 `_ 208 | * Copying action generators from actionlib to actionlib_msgs 209 | * updating review status 210 | * Updating actionlib_msgs comments (`#3003 `_) 211 | * filling out manifest 212 | * Documenting GoalStatus message 213 | * Forgot to commit files to actionlib_msgs 214 | * Moving actionlib messages into common_msgs/actionlib_msgs. Trac `#2504 `_ 215 | -------------------------------------------------------------------------------- /actionlib_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(actionlib_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS message_generation std_msgs) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | GoalID.msg 10 | GoalStatus.msg 11 | GoalStatusArray.msg) 12 | generate_messages(DEPENDENCIES std_msgs) 13 | 14 | catkin_package( 15 | CATKIN_DEPENDS message_runtime std_msgs 16 | CFG_EXTRAS actionlib_msgs-extras.cmake) 17 | 18 | # install the .action -> .msg generator 19 | catkin_install_python(PROGRAMS scripts/genaction.py 20 | DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) 21 | 22 | # install the legacy rosbuild cmake support 23 | install(FILES cmake/actionbuild.cmake 24 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/cmake) 25 | -------------------------------------------------------------------------------- /actionlib_msgs/cmake/actionbuild.cmake: -------------------------------------------------------------------------------- 1 | # THIS FILE CANNOT BE MOVED. Users include it like so: 2 | # rosbuild_find_ros_package(actionlib_msgs) 3 | # include(${actionlib_msgs_PACKAGE_PATH}/cmake/actionbuild.cmake) 4 | 5 | macro(get_actions actionvar) 6 | file(GLOB _action_files RELATIVE "${PROJECT_SOURCE_DIR}/action" "${PROJECT_SOURCE_DIR}/action/*.action") 7 | message(STATUS "Action Files:" ${_action_files}) 8 | foreach(_action ${_action_files}) 9 | if(${_action} MATCHES "^[^\\.].*\\.action$") 10 | list(APPEND ${actionvar} ${_action}) 11 | endif(${_action} MATCHES "^[^\\.].*\\.action$") 12 | endforeach(_action) 13 | endmacro(get_actions) 14 | 15 | macro(genaction) 16 | if(ROSBUILD_init_called) 17 | message(FATAL_ERROR "genaction() cannot be called after rosbuild_init(), please change the order in your CMakeLists.txt file.") 18 | endif(ROSBUILD_init_called) 19 | get_actions(_actionlist) 20 | set(_autogen "") 21 | set(_autogen_msg_list "") 22 | foreach(_action ${_actionlist}) 23 | message(STATUS "Generating Messages for Action" ${_action}) 24 | #construct the path to the .action file 25 | set(_input ${PROJECT_SOURCE_DIR}/action/${_action}) 26 | 27 | string(REPLACE ".action" "" _action_bare ${_action}) 28 | 29 | # get path to action generator script 30 | find_package(catkin REQUIRED COMPONENTS actionlib_msgs) 31 | 32 | #We have to do this because message generation assumes filenames without full paths 33 | set(_base_output_action ${_action_bare}Action.msg) 34 | set(_base_output_goal ${_action_bare}Goal.msg) 35 | set(_base_output_action_goal ${_action_bare}ActionGoal.msg) 36 | set(_base_output_result ${_action_bare}Result.msg) 37 | set(_base_output_action_result ${_action_bare}ActionResult.msg) 38 | set(_base_output_feedback ${_action_bare}Feedback.msg) 39 | set(_base_output_action_feedback ${_action_bare}ActionFeedback.msg) 40 | 41 | set(_output_action ${PROJECT_SOURCE_DIR}/msg/${_base_output_action}) 42 | set(_output_goal ${PROJECT_SOURCE_DIR}/msg/${_base_output_goal}) 43 | set(_output_action_goal ${PROJECT_SOURCE_DIR}/msg/${_base_output_action_goal}) 44 | set(_output_result ${PROJECT_SOURCE_DIR}/msg/${_base_output_result}) 45 | set(_output_action_result ${PROJECT_SOURCE_DIR}/msg/${_base_output_action_result}) 46 | set(_output_feedback ${PROJECT_SOURCE_DIR}/msg/${_base_output_feedback}) 47 | set(_output_action_feedback ${PROJECT_SOURCE_DIR}/msg/${_base_output_action_feedback}) 48 | message(STATUS ${_output_action}) 49 | 50 | add_custom_command( 51 | OUTPUT ${_output_action} ${_output_goal} ${_output_action_goal} ${_output_result} ${_output_action_result} ${_output_feedback} ${_output_action_feedback} 52 | COMMAND ${GENACTION_BIN} ${_input} -o ${PROJECT_SOURCE_DIR}/msg 53 | DEPENDS ${_input} ${GENACTION_BIN} ${ROS_MANIFEST_LIST} 54 | ) 55 | list(APPEND _autogen ${_output_action} ${_output_goal} ${_output_action_goal} ${_output_result} ${_output_action_result} ${_output_feedback} ${_output_action_feedback}) 56 | list(APPEND _autogen_msg_list ${_base_output_action} ${_base_output_goal} ${_base_output_action_goal} ${_base_output_result} ${_base_output_action_result} ${_base_output_feedback} ${_base_output_action_feedback}) 57 | endforeach(_action) 58 | 59 | # Create a target that depends on the union of all the autogenerated files 60 | add_custom_target(ROSBUILD_genaction_msgs ALL DEPENDS ${_autogen}) 61 | add_custom_target(rosbuild_premsgsrvgen) 62 | add_dependencies(rosbuild_premsgsrvgen ROSBUILD_genaction_msgs) 63 | rosbuild_add_generated_msgs(${_autogen_msg_list}) 64 | endmacro(genaction) 65 | -------------------------------------------------------------------------------- /actionlib_msgs/cmake/actionlib_msgs-extras.cmake.em: -------------------------------------------------------------------------------- 1 | # need genmsg for _prepend_path() 2 | find_package(genmsg REQUIRED) 3 | 4 | include(CMakeParseArguments) 5 | 6 | @[if DEVELSPACE]@ 7 | # program in develspace 8 | set(GENACTION_BIN "@(CMAKE_CURRENT_SOURCE_DIR)/scripts/genaction.py") 9 | @[else]@ 10 | # program in installspace 11 | set(GENACTION_BIN "${actionlib_msgs_DIR}/../../../@(CATKIN_PACKAGE_BIN_DESTINATION)/genaction.py") 12 | @[end if]@ 13 | 14 | macro(add_action_files) 15 | cmake_parse_arguments(ARG "NOINSTALL" "DIRECTORY" "FILES" ${ARGN}) 16 | if(ARG_UNPARSED_ARGUMENTS) 17 | message(FATAL_ERROR "add_action_files() called with unused arguments: ${ARG_UNPARSED_ARGUMENTS}") 18 | endif() 19 | 20 | if(NOT ARG_DIRECTORY) 21 | set(ARG_DIRECTORY "action") 22 | endif() 23 | 24 | if(NOT IS_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/${ARG_DIRECTORY}) 25 | message(FATAL_ERROR "add_action_files() directory not found: ${CMAKE_CURRENT_SOURCE_DIR}/${ARG_DIRECTORY}") 26 | endif() 27 | 28 | # if FILES are not passed search action files in the given directory 29 | # note: ARGV is not variable, so it can not be passed to list(FIND) directly 30 | set(_argv ${ARGV}) 31 | list(FIND _argv "FILES" _index) 32 | if(_index EQUAL -1) 33 | file(GLOB ARG_FILES RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}/${ARG_DIRECTORY}" "${CMAKE_CURRENT_SOURCE_DIR}/${ARG_DIRECTORY}/*.action") 34 | list(SORT ARG_FILES) 35 | endif() 36 | _prepend_path(${CMAKE_CURRENT_SOURCE_DIR}/${ARG_DIRECTORY} "${ARG_FILES}" FILES_W_PATH) 37 | 38 | list(APPEND ${PROJECT_NAME}_ACTION_FILES ${FILES_W_PATH}) 39 | foreach(file ${FILES_W_PATH}) 40 | assert_file_exists(${file} "action file not found") 41 | endforeach() 42 | 43 | if(NOT ARG_NOINSTALL) 44 | install(FILES ${FILES_W_PATH} DESTINATION share/${PROJECT_NAME}/${ARG_DIRECTORY}) 45 | endif() 46 | 47 | foreach(actionfile ${FILES_W_PATH}) 48 | if(NOT CATKIN_DEVEL_PREFIX) 49 | message(FATAL_ERROR "Assertion failed: 'CATKIN_DEVEL_PREFIX' is not set") 50 | endif() 51 | get_filename_component(ACTION_SHORT_NAME ${actionfile} NAME_WE) 52 | set(MESSAGE_DIR ${CATKIN_DEVEL_PREFIX}/share/${PROJECT_NAME}/msg) 53 | set(OUTPUT_FILES 54 | ${ACTION_SHORT_NAME}Action.msg 55 | ${ACTION_SHORT_NAME}ActionGoal.msg 56 | ${ACTION_SHORT_NAME}ActionResult.msg 57 | ${ACTION_SHORT_NAME}ActionFeedback.msg 58 | ${ACTION_SHORT_NAME}Goal.msg 59 | ${ACTION_SHORT_NAME}Result.msg 60 | ${ACTION_SHORT_NAME}Feedback.msg) 61 | 62 | _prepend_path(${MESSAGE_DIR}/ "${OUTPUT_FILES}" OUTPUT_FILES_W_PATH) 63 | 64 | message(STATUS "Generating .msg files for action ${PROJECT_NAME}/${ACTION_SHORT_NAME} ${actionfile}") 65 | 66 | stamp(${actionfile}) 67 | 68 | if(NOT CATKIN_ENV) 69 | message(FATAL_ERROR "Assertion failed: 'CATKIN_ENV' is not set") 70 | endif() 71 | if(${actionfile} IS_NEWER_THAN ${MESSAGE_DIR}/${ACTION_SHORT_NAME}Action.msg) 72 | safe_execute_process(COMMAND ${CATKIN_ENV} ${PYTHON_EXECUTABLE} ${GENACTION_BIN} ${actionfile} -o ${MESSAGE_DIR}) 73 | endif() 74 | 75 | add_message_files( 76 | BASE_DIR ${MESSAGE_DIR} 77 | FILES ${OUTPUT_FILES}) 78 | endforeach() 79 | endmacro() 80 | -------------------------------------------------------------------------------- /actionlib_msgs/msg/GoalID.msg: -------------------------------------------------------------------------------- 1 | # The stamp should store the time at which this goal was requested. 2 | # It is used by an action server when it tries to preempt all 3 | # goals that were requested before a certain time 4 | time stamp 5 | 6 | # The id provides a way to associate feedback and 7 | # result message with specific goal requests. The id 8 | # specified must be unique. 9 | string id 10 | 11 | -------------------------------------------------------------------------------- /actionlib_msgs/msg/GoalStatus.msg: -------------------------------------------------------------------------------- 1 | GoalID goal_id 2 | uint8 status 3 | uint8 PENDING = 0 # The goal has yet to be processed by the action server 4 | uint8 ACTIVE = 1 # The goal is currently being processed by the action server 5 | uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing 6 | # and has since completed its execution (Terminal State) 7 | uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) 8 | uint8 ABORTED = 4 # The goal was aborted during execution by the action server due 9 | # to some failure (Terminal State) 10 | uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, 11 | # because the goal was unattainable or invalid (Terminal State) 12 | uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing 13 | # and has not yet completed execution 14 | uint8 RECALLING = 7 # The goal received a cancel request before it started executing, 15 | # but the action server has not yet confirmed that the goal is canceled 16 | uint8 RECALLED = 8 # The goal received a cancel request before it started executing 17 | # and was successfully cancelled (Terminal State) 18 | uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be 19 | # sent over the wire by an action server 20 | 21 | #Allow for the user to associate a string with GoalStatus for debugging 22 | string text 23 | 24 | -------------------------------------------------------------------------------- /actionlib_msgs/msg/GoalStatusArray.msg: -------------------------------------------------------------------------------- 1 | # Stores the statuses for goals that are currently being tracked 2 | # by an action server 3 | Header header 4 | GoalStatus[] status_list 5 | 6 | -------------------------------------------------------------------------------- /actionlib_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | actionlib_msgs 3 | 1.13.2 4 | 5 | actionlib_msgs defines the common messages to interact with an 6 | action server and an action client. For full documentation of 7 | the actionlib API see 8 | the actionlib 9 | package. 10 | 11 | Michel Hidalgo 12 | BSD 13 | 14 | http://wiki.ros.org/actionlib_msgs 15 | Vijay Pradeep 16 | Tully Foote 17 | 18 | catkin 19 | 20 | message_generation 21 | std_msgs 22 | 23 | message_generation 24 | message_runtime 25 | std_msgs 26 | 27 | 28 | 29 | 30 | 31 | -------------------------------------------------------------------------------- /actionlib_msgs/scripts/genaction.py: -------------------------------------------------------------------------------- 1 | #! /usr/bin/env python 2 | # Copyright (c) 2009, Willow Garage, Inc. 3 | # All rights reserved. 4 | # 5 | # Redistribution and use in source and binary forms, with or without 6 | # modification, are permitted provided that the following conditions are met: 7 | # 8 | # * Redistributions of source code must retain the above copyright 9 | # notice, this list of conditions and the following disclaimer. 10 | # * Redistributions in binary form must reproduce the above copyright 11 | # notice, this list of conditions and the following disclaimer in the 12 | # documentation and/or other materials provided with the distribution. 13 | # * Neither the name of the Willow Garage, Inc. nor the names of its 14 | # contributors may be used to endorse or promote products derived from 15 | # this software without specific prior written permission. 16 | # 17 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 18 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 19 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 20 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 21 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 22 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 23 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 24 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 25 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 26 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 27 | # POSSIBILITY OF SUCH DAMAGE. 28 | 29 | # Author: Stuart Glaser 30 | 31 | import sys 32 | try: 33 | from cStringIO import StringIO 34 | except ImportError: 35 | from io import StringIO 36 | import re 37 | import os, os.path 38 | import errno 39 | from optparse import OptionParser 40 | 41 | IODELIM = '---' 42 | AUTOGEN="# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n" 43 | 44 | class ActionSpecException(Exception): pass 45 | 46 | def parse_action_spec(text, package_context = ''): 47 | pieces = [StringIO()] 48 | for l in text.split('\n'): 49 | if l.startswith(IODELIM): 50 | pieces.append(StringIO()) 51 | else: 52 | pieces[-1].write(l + '\n') 53 | return [p.getvalue() for p in pieces] 54 | 55 | def write_file(filename, text): 56 | f = open(filename, 'w') 57 | f.write(text) 58 | f.close() 59 | 60 | def main(): 61 | 62 | parser = OptionParser("Actionlib generator") 63 | parser.add_option('-o', dest='output_dir', 64 | help='output directory') 65 | 66 | (options, args) = parser.parse_args(sys.argv) 67 | 68 | pkg = os.path.abspath(sys.argv[1]) 69 | filename = sys.argv[2] 70 | 71 | output_dir = options.output_dir 72 | 73 | # Try to make the directory, but silently continue if it already exists 74 | try: 75 | os.makedirs(output_dir) 76 | except OSError as e: 77 | if e.errno == errno.EEXIST: 78 | pass 79 | else: 80 | raise 81 | 82 | action_file = args[1] 83 | if not action_file.endswith('.action'): 84 | print("The file specified has the wrong extension. It must end in .action") 85 | else: 86 | filename = action_file 87 | 88 | f = open(filename) 89 | action_spec = f.read() 90 | f.close() 91 | 92 | name = os.path.basename(filename)[:-7] 93 | print("Generating for action %s" % name) 94 | 95 | pieces = parse_action_spec(action_spec) 96 | if len(pieces) != 3: 97 | raise ActionSpecException("%s: wrong number of pieces, %d"%(filename,len(pieces))) 98 | goal, result, feedback = pieces 99 | 100 | action_msg = AUTOGEN + """ 101 | %sActionGoal action_goal 102 | %sActionResult action_result 103 | %sActionFeedback action_feedback 104 | """ % (name, name, name) 105 | 106 | goal_msg = AUTOGEN + goal 107 | action_goal_msg = AUTOGEN + """ 108 | Header header 109 | actionlib_msgs/GoalID goal_id 110 | %sGoal goal 111 | """ % name 112 | 113 | result_msg = AUTOGEN + result 114 | action_result_msg = AUTOGEN + """ 115 | Header header 116 | actionlib_msgs/GoalStatus status 117 | %sResult result 118 | """ % name 119 | 120 | feedback_msg = AUTOGEN + feedback 121 | action_feedback_msg = AUTOGEN + """ 122 | Header header 123 | actionlib_msgs/GoalStatus status 124 | %sFeedback feedback 125 | """ % name 126 | 127 | write_file(os.path.join(output_dir, "%sAction.msg"%name), action_msg) 128 | write_file(os.path.join(output_dir, "%sGoal.msg"%name), goal_msg) 129 | write_file(os.path.join(output_dir, "%sActionGoal.msg"%name), action_goal_msg) 130 | write_file(os.path.join(output_dir, "%sResult.msg"%name), result_msg) 131 | write_file(os.path.join(output_dir, "%sActionResult.msg"%name), action_result_msg) 132 | write_file(os.path.join(output_dir, "%sFeedback.msg"%name), feedback_msg) 133 | write_file(os.path.join(output_dir, "%sActionFeedback.msg"%name), action_feedback_msg) 134 | 135 | 136 | if __name__ == '__main__': main() 137 | -------------------------------------------------------------------------------- /common_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package common_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.13.2 (2025-04-25) 6 | ------------------- 7 | 8 | 1.13.1 (2021-01-11) 9 | ------------------- 10 | * Update package maintainers (`#168 `_) 11 | * Contributors: Michel Hidalgo 12 | 13 | 1.13.0 (2020-05-21) 14 | ------------------- 15 | * Bump CMake version to avoid CMP0048 warning (`#158 `_) 16 | * Contributors: Shane Loretz 17 | 18 | 1.12.7 (2018-11-06) 19 | ------------------- 20 | 21 | 1.12.6 (2018-05-03) 22 | ------------------- 23 | 24 | 1.12.5 (2016-09-30) 25 | ------------------- 26 | 27 | 1.12.4 (2016-02-22) 28 | ------------------- 29 | 30 | 1.12.3 (2015-04-20) 31 | ------------------- 32 | 33 | 1.12.2 (2015-03-21) 34 | ------------------- 35 | 36 | 1.12.1 (2015-03-17) 37 | ------------------- 38 | * updating outdated urls. fixes `#52 `_. 39 | * Contributors: Tully Foote 40 | 41 | 1.12.0 (2014-12-29) 42 | ------------------- 43 | 44 | 1.11.6 (2014-11-04) 45 | ------------------- 46 | 47 | 1.11.5 (2014-10-27) 48 | ------------------- 49 | 50 | 1.11.4 (2014-06-19) 51 | ------------------- 52 | 53 | 1.11.3 (2014-05-07) 54 | ------------------- 55 | 56 | 1.11.2 (2014-04-24) 57 | ------------------- 58 | 59 | 1.11.1 (2014-04-16) 60 | ------------------- 61 | 62 | 1.11.0 (2014-03-04) 63 | ------------------- 64 | 65 | 1.10.6 (2014-02-27) 66 | ------------------- 67 | 68 | 1.10.5 (2014-02-25) 69 | ------------------- 70 | 71 | 1.10.4 (2014-02-18) 72 | ------------------- 73 | 74 | 1.10.3 (2014-01-07) 75 | ------------------- 76 | 77 | 1.10.2 (2013-08-19) 78 | ------------------- 79 | 80 | 1.10.1 (2013-08-16) 81 | ------------------- 82 | 83 | 1.10.0 (2013-07-13) 84 | ------------------- 85 | 86 | 1.9.16 (2013-05-21) 87 | ------------------- 88 | * add buildtool dep on catkin for metapackage 89 | * update email in package.xml 90 | 91 | 1.9.15 (2013-03-08) 92 | ------------------- 93 | * add CMakeLists.txt for metapackage 94 | 95 | 1.9.14 (2013-01-19) 96 | ------------------- 97 | 98 | 1.9.13 (2013-01-13) 99 | ------------------- 100 | 101 | 1.9.12 (2013-01-02) 102 | ------------------- 103 | 104 | 1.9.11 (2012-12-17) 105 | ------------------- 106 | 107 | 1.9.10 (2012-12-13) 108 | ------------------- 109 | 110 | 1.9.9 (2012-11-22) 111 | ------------------ 112 | 113 | 1.9.8 (2012-11-14) 114 | ------------------ 115 | 116 | 1.9.7 (2012-10-30) 117 | ------------------ 118 | 119 | 1.9.6 (2012-10-18) 120 | ------------------ 121 | 122 | 1.9.5 (2012-09-28) 123 | ------------------ 124 | 125 | 1.9.4 (2012-09-27 18:06) 126 | ------------------------ 127 | * fix dependency name 128 | 129 | 1.9.3 (2012-09-27 17:39) 130 | ------------------------ 131 | * cleanup 132 | * cleaned up package.xml files 133 | * fixed dependencies and more 134 | * updated to latest catkin: created package.xmls, updated CmakeLists.txt 135 | 136 | 1.9.2 (2012-09-05) 137 | ------------------ 138 | 139 | 1.9.1 (2012-09-04) 140 | ------------------ 141 | 142 | 1.9.0 (2012-08-29) 143 | ------------------ 144 | 145 | 1.8.13 (2012-07-26 18:34:15 +0000) 146 | ---------------------------------- 147 | 148 | 1.8.8 (2012-06-12 22:36) 149 | ------------------------ 150 | -------------------------------------------------------------------------------- /common_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(common_msgs) 3 | find_package(catkin REQUIRED) 4 | catkin_metapackage() 5 | -------------------------------------------------------------------------------- /common_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | common_msgs 3 | 1.13.2 4 | 5 | common_msgs contains messages that are widely used by other ROS packages. 6 | These includes messages for 7 | actions (actionlib_msgs), 8 | diagnostics (diagnostic_msgs), 9 | geometric primitives (geometry_msgs), 10 | robot navigation (nav_msgs), 11 | and common sensors (sensor_msgs), such as laser range finders, cameras, point clouds. 12 | 13 | Michel Hidalgo 14 | BSD 15 | 16 | http://wiki.ros.org/common_msgs 17 | Tully Foote 18 | 19 | catkin 20 | 21 | actionlib_msgs 22 | diagnostic_msgs 23 | geometry_msgs 24 | nav_msgs 25 | sensor_msgs 26 | shape_msgs 27 | stereo_msgs 28 | trajectory_msgs 29 | visualization_msgs 30 | 31 | 32 | 33 | 34 | 35 | -------------------------------------------------------------------------------- /diagnostic_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package diagnostic_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.13.2 (2025-04-25) 6 | ------------------- 7 | 8 | 1.13.1 (2021-01-11) 9 | ------------------- 10 | * Update package maintainers (`#168 `_) 11 | * Contributors: Michel Hidalgo 12 | 13 | 1.13.0 (2020-05-21) 14 | ------------------- 15 | * Bump CMake version to avoid CMP0048 warning (`#158 `_) 16 | * Contributors: Shane Loretz 17 | 18 | 1.12.7 (2018-11-06) 19 | ------------------- 20 | 21 | 1.12.6 (2018-05-03) 22 | ------------------- 23 | 24 | 1.12.5 (2016-09-30) 25 | ------------------- 26 | 27 | 1.12.4 (2016-02-22) 28 | ------------------- 29 | * diagnostic_msgs: Add messages for service used to add diagnostics to aggregator 30 | * Contributors: Michal Staniaszek 31 | 32 | 1.12.3 (2015-04-20) 33 | ------------------- 34 | 35 | 1.12.2 (2015-03-21) 36 | ------------------- 37 | 38 | 1.12.1 (2015-03-17) 39 | ------------------- 40 | * updating outdated urls. fixes `#52 `_. 41 | * Contributors: Tully Foote 42 | 43 | 1.12.0 (2014-12-29) 44 | ------------------- 45 | 46 | 1.11.6 (2014-11-04) 47 | ------------------- 48 | 49 | 1.11.5 (2014-10-27) 50 | ------------------- 51 | 52 | 1.11.4 (2014-06-19) 53 | ------------------- 54 | 55 | 1.11.3 (2014-05-07) 56 | ------------------- 57 | * Export architecture_independent flag in package.xml 58 | * Contributors: Scott K Logan 59 | 60 | 1.11.2 (2014-04-24) 61 | ------------------- 62 | * Add STALE to DiagnosticStatus level enum 63 | * Contributors: Austin 64 | 65 | 1.11.1 (2014-04-16) 66 | ------------------- 67 | 68 | 1.11.0 (2014-03-04) 69 | ------------------- 70 | 71 | 1.10.6 (2014-02-27) 72 | ------------------- 73 | 74 | 1.10.5 (2014-02-25) 75 | ------------------- 76 | 77 | 1.10.4 (2014-02-18) 78 | ------------------- 79 | 80 | 1.10.3 (2014-01-07) 81 | ------------------- 82 | 83 | 1.10.2 (2013-08-19) 84 | ------------------- 85 | 86 | 1.10.1 (2013-08-16) 87 | ------------------- 88 | 89 | 1.10.0 (2013-07-13) 90 | ------------------- 91 | 92 | 1.9.16 (2013-05-21) 93 | ------------------- 94 | * update email in package.xml 95 | 96 | 1.9.15 (2013-03-08) 97 | ------------------- 98 | 99 | 1.9.14 (2013-01-19) 100 | ------------------- 101 | 102 | 1.9.13 (2013-01-13) 103 | ------------------- 104 | 105 | 1.9.12 (2013-01-02) 106 | ------------------- 107 | 108 | 1.9.11 (2012-12-17) 109 | ------------------- 110 | * modified dep type of catkin 111 | 112 | 1.9.10 (2012-12-13) 113 | ------------------- 114 | * add missing downstream depend 115 | * switched from langs to message_* packages 116 | 117 | 1.9.9 (2012-11-22) 118 | ------------------ 119 | 120 | 1.9.8 (2012-11-14) 121 | ------------------ 122 | 123 | 1.9.7 (2012-10-30) 124 | ------------------ 125 | * fix catkin function order 126 | 127 | 1.9.6 (2012-10-18) 128 | ------------------ 129 | * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 130 | 131 | 1.9.5 (2012-09-28) 132 | ------------------ 133 | 134 | 1.9.4 (2012-09-27 18:06) 135 | ------------------------ 136 | 137 | 1.9.3 (2012-09-27 17:39) 138 | ------------------------ 139 | * cleanup 140 | * updated to latest catkin 141 | * fixed dependencies and more 142 | * updated to latest catkin: created package.xmls, updated CmakeLists.txt 143 | 144 | 1.9.2 (2012-09-05) 145 | ------------------ 146 | * updated pkg-config in manifest.xml 147 | 148 | 1.9.1 (2012-09-04) 149 | ------------------ 150 | * use install destination variables, removed manual installation of manifests 151 | 152 | 1.9.0 (2012-08-29) 153 | ------------------ 154 | 155 | 1.8.13 (2012-07-26 18:34:15 +0000) 156 | ---------------------------------- 157 | 158 | 1.8.8 (2012-06-12 22:36) 159 | ------------------------ 160 | * removed obsolete catkin tag from manifest files 161 | * adding manifest exports 162 | * removed depend, added catkin 163 | * stripping depend and export tags from common_msgs manifests as msg dependencies are now declared in cmake and stack.yaml. Also removed bag migration exports 164 | * common_msgs: removing migration rules as all are over a year old 165 | * bye bye vestigial MSG_DIRS 166 | * diagnostic_msgs: catkin'd 167 | * adios rosbuild2 in manifest.xml 168 | * missing dependencies 169 | * updating bagmigration exports 170 | * rosbuild2 taking shape 171 | * removing all the extra exports 172 | * Added Ubuntu platform tags to manifest 173 | * fixed manifest description 174 | * Remove use of deprecated rosbuild macros 175 | * changing review status 176 | * adding comment about stability for doc review 177 | * fixing link and wrapping lines 178 | * updated description and url 179 | * filling out description 180 | * documenting DiagnosticStatus and DiagnosticArray. setting proper constants for level of operation. bag migrations passes (incorrectly) ticketing Jeremy 181 | * Changing naming of bag migration rules. 182 | * Removing cross-stack dependency of test_common_msgs on pr2_msgs, and fixing diagnostic_msgs migration rules due to change in KeyValue. 183 | * Change KeyValue to actually be key/value 184 | * Adding more migration rule tests and fixing assorted rules. 185 | * fixing through diagnostic_updater 186 | * Fix DiagnosticStatus 187 | * removing DiagnosticString and DiagnosticValue and last few references to them `#1903 `_ 188 | * Changed DiagnosticMessage to DiagnosticArray 189 | * adding KeyValue for Blaise --Tully 190 | * Changed DiagnosticValue to KeyValue 191 | * merging in the changes to messages see ros-users email. THis is about half the common_msgs API changes 192 | * populating common_msgs 193 | -------------------------------------------------------------------------------- /diagnostic_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(diagnostic_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS message_generation std_msgs) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | DiagnosticArray.msg 10 | DiagnosticStatus.msg 11 | KeyValue.msg) 12 | 13 | add_service_files( 14 | DIRECTORY srv 15 | FILES 16 | AddDiagnostics.srv 17 | SelfTest.srv) 18 | 19 | generate_messages(DEPENDENCIES std_msgs) 20 | 21 | catkin_package(CATKIN_DEPENDS message_runtime std_msgs) 22 | -------------------------------------------------------------------------------- /diagnostic_msgs/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | \b diagnostic_msgs is a package to hold the diagnostic messages 6 | 7 | These messages are used by the runtime diagnostics system. 8 | 9 | See the wiki at http://wiki.ros.org/diagnostic_msgs for a summary of the messages. 10 | 11 | And the diagnostic system is documented at http://wiki.ros.org/Diagnostics 12 | 13 | */ -------------------------------------------------------------------------------- /diagnostic_msgs/msg/DiagnosticArray.msg: -------------------------------------------------------------------------------- 1 | # This message is used to send diagnostic information about the state of the robot 2 | Header header #for timestamp 3 | DiagnosticStatus[] status # an array of components being reported on -------------------------------------------------------------------------------- /diagnostic_msgs/msg/DiagnosticStatus.msg: -------------------------------------------------------------------------------- 1 | # This message holds the status of an individual component of the robot. 2 | # 3 | 4 | # Possible levels of operations 5 | byte OK=0 6 | byte WARN=1 7 | byte ERROR=2 8 | byte STALE=3 9 | 10 | byte level # level of operation enumerated above 11 | string name # a description of the test/component reporting 12 | string message # a description of the status 13 | string hardware_id # a hardware unique string 14 | KeyValue[] values # an array of values associated with the status 15 | 16 | -------------------------------------------------------------------------------- /diagnostic_msgs/msg/KeyValue.msg: -------------------------------------------------------------------------------- 1 | string key # what to label this value when viewing 2 | string value # a value to track over time 3 | -------------------------------------------------------------------------------- /diagnostic_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | diagnostic_msgs 3 | 1.13.2 4 | 5 | This package holds the diagnostic messages which provide the 6 | standardized interface for the diagnostic and runtime monitoring 7 | systems in ROS. These messages are currently used by 8 | the diagnostics 9 | Stack, which provides libraries for simple ways to set and access 10 | the messages, as well as automated ways to process the diagnostic 11 | data. 12 | 13 | These messages are used for long term logging and will not be 14 | changed unless there is a very important reason. 15 | 16 | Michel Hidalgo 17 | BSD 18 | 19 | http://wiki.ros.org/diagnostic_msgs 20 | Tully Foote 21 | 22 | catkin 23 | 24 | message_generation 25 | std_msgs 26 | 27 | message_runtime 28 | std_msgs 29 | 30 | 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /diagnostic_msgs/srv/AddDiagnostics.srv: -------------------------------------------------------------------------------- 1 | # This service is used as part of the process for loading analyzers at runtime, 2 | # and should be used by a loader script or program, not as a standalone service. 3 | # Information about dynamic addition of analyzers can be found at 4 | # http://wiki.ros.org/diagnostics/Tutorials/Adding%20Analyzers%20at%20Runtime 5 | 6 | # The load_namespace parameter defines the namespace where parameters for the 7 | # initialization of analyzers in the diagnostic aggregator have been loaded. The 8 | # value should be a global name (i.e. /my/name/space), not a relative 9 | # (my/name/space) or private (~my/name/space) name. Analyzers will not be added 10 | # if a non-global name is used. The call will also fail if the namespace 11 | # contains parameters that follow a namespace structure that does not conform to 12 | # that expected by the analyzer definitions. See 13 | # http://wiki.ros.org/diagnostics/Tutorials/Configuring%20Diagnostic%20Aggregators 14 | # and http://wiki.ros.org/diagnostics/Tutorials/Using%20the%20GenericAnalyzer 15 | # for examples of the structure of yaml files which are expected to have been 16 | # loaded into the namespace. 17 | string load_namespace 18 | --- 19 | 20 | # True if diagnostic aggregator was updated with new diagnostics, False 21 | # otherwise. A false return value means that either there is a bond in the 22 | # aggregator which already used the requested namespace, or the initialization 23 | # of analyzers failed. 24 | bool success 25 | 26 | # Message with additional information about the success or failure 27 | string message 28 | -------------------------------------------------------------------------------- /diagnostic_msgs/srv/SelfTest.srv: -------------------------------------------------------------------------------- 1 | --- 2 | string id 3 | byte passed 4 | DiagnosticStatus[] status 5 | -------------------------------------------------------------------------------- /geometry_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package geometry_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.13.2 (2025-04-25) 6 | ------------------- 7 | * Remove additional spaces (`#180 `_) 8 | * Contributors: Oskar 9 | 10 | 1.13.1 (2021-01-11) 11 | ------------------- 12 | * Update package maintainers (`#168 `_) 13 | * Contributors: Michel Hidalgo 14 | 15 | 1.13.0 (2020-05-21) 16 | ------------------- 17 | * Bump CMake version to avoid CMP0048 warning (`#158 `_) 18 | * Contributors: Shane Loretz 19 | 20 | 1.12.7 (2018-11-06) 21 | ------------------- 22 | * Add deprecation comment about Pose2D (`#130 `_) 23 | It started as unused and still isn't recommended. 24 | Followup to `#129 `_ 25 | * Contributors: Tully Foote 26 | 27 | 1.12.6 (2018-05-03) 28 | ------------------- 29 | 30 | 1.12.5 (2016-09-30) 31 | ------------------- 32 | * Fix spelling mistakes 33 | * Contributors: trorornmn 34 | 35 | 1.12.4 (2016-02-22) 36 | ------------------- 37 | * clarify the definition of a Vector3 38 | * Contributors: Vincent Rabaud 39 | 40 | 1.12.3 (2015-04-20) 41 | ------------------- 42 | * geometry_msgs/InertiaStamped uses geometry_msgs/Inertia. 43 | * Contributors: Gayane Kazhoyan, Georg Bartels 44 | 45 | 1.12.2 (2015-03-21) 46 | ------------------- 47 | * Add Accel, AccelStamped, AccelWithCovariance, AccelWithCovarianceStamped message definitions 48 | * Add Inertia and InertiaStamped messages 49 | * Contributors: Jonathan Bohren, Paul Bovbel 50 | 51 | 1.12.1 (2015-03-17) 52 | ------------------- 53 | * updating outdated urls. fixes `#52 `_. 54 | * Contributors: Tully Foote 55 | 56 | 1.12.0 (2014-12-29) 57 | ------------------- 58 | 59 | 1.11.6 (2014-11-04) 60 | ------------------- 61 | 62 | 1.11.5 (2014-10-27) 63 | ------------------- 64 | 65 | 1.11.4 (2014-06-19) 66 | ------------------- 67 | 68 | 1.11.3 (2014-05-07) 69 | ------------------- 70 | * Export architecture_independent flag in package.xml 71 | * Contributors: Scott K Logan 72 | 73 | 1.11.2 (2014-04-24) 74 | ------------------- 75 | 76 | 1.11.1 (2014-04-16) 77 | ------------------- 78 | 79 | 1.11.0 (2014-03-04) 80 | ------------------- 81 | 82 | 1.10.6 (2014-02-27) 83 | ------------------- 84 | 85 | 1.10.5 (2014-02-25) 86 | ------------------- 87 | 88 | 1.10.4 (2014-02-18) 89 | ------------------- 90 | 91 | 1.10.3 (2014-01-07) 92 | ------------------- 93 | 94 | 1.10.2 (2013-08-19) 95 | ------------------- 96 | 97 | 1.10.1 (2013-08-16) 98 | ------------------- 99 | 100 | 1.10.0 (2013-07-13) 101 | ------------------- 102 | 103 | 1.9.16 (2013-05-21) 104 | ------------------- 105 | * update email in package.xml 106 | 107 | 1.9.15 (2013-03-08) 108 | ------------------- 109 | 110 | 1.9.14 (2013-01-19) 111 | ------------------- 112 | 113 | 1.9.13 (2013-01-13) 114 | ------------------- 115 | * fix spelling in comments (fix `#3194 `_) 116 | 117 | 1.9.12 (2013-01-02) 118 | ------------------- 119 | 120 | 1.9.11 (2012-12-17) 121 | ------------------- 122 | * modified dep type of catkin 123 | 124 | 1.9.10 (2012-12-13) 125 | ------------------- 126 | * add missing downstream depend 127 | * switched from langs to message_* packages 128 | 129 | 1.9.9 (2012-11-22) 130 | ------------------ 131 | 132 | 1.9.8 (2012-11-14) 133 | ------------------ 134 | 135 | 1.9.7 (2012-10-30) 136 | ------------------ 137 | * fix catkin function order 138 | 139 | 1.9.6 (2012-10-18) 140 | ------------------ 141 | * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 142 | 143 | 1.9.5 (2012-09-28) 144 | ------------------ 145 | 146 | 1.9.4 (2012-09-27 18:06) 147 | ------------------------ 148 | 149 | 1.9.3 (2012-09-27 17:39) 150 | ------------------------ 151 | * cleanup 152 | * cleaned up package.xml files 153 | * updated to latest catkin 154 | * fixed dependencies and more 155 | * updated to latest catkin: created package.xmls, updated CmakeLists.txt 156 | 157 | 1.9.2 (2012-09-05) 158 | ------------------ 159 | * updated pkg-config in manifest.xml 160 | 161 | 1.9.1 (2012-09-04) 162 | ------------------ 163 | * use install destination variables, removed manual installation of manifests 164 | 165 | 1.9.0 (2012-08-29) 166 | ------------------ 167 | 168 | 1.8.13 (2012-07-26 18:34:15 +0000) 169 | ---------------------------------- 170 | 171 | 1.8.8 (2012-06-12 22:36) 172 | ------------------------ 173 | * removed obsolete catkin tag from manifest files 174 | * removed unnecessary package name from some messages 175 | * adding manifest exports 176 | * removed depend, added catkin 177 | * stripping depend and export tags from common_msgs manifests as msg dependencies are now declared in cmake and stack.yaml. Also removed bag migration exports 178 | * install-related fixes 179 | * common_msgs: removing migration rules as all are over a year old 180 | * bye bye vestigial MSG_DIRS 181 | * geometry_msgs: getting rid of other build files 182 | * updated to new catkin_export_python macro 183 | * adios rosbuild2 in manifest.xml 184 | * catkin updates 185 | * catkin_project 186 | * Updated to work with new message generation macros 187 | * adios debian/ hello stack.yaml. (sketch/prototype/testing). 188 | * Getting standalone message generation working... w/o munging rosbuild2 189 | * rosbuild2 tweaks 190 | * initial updating for new light message generation and wgbuild 191 | * missing dependencies 192 | * updating bagmigration exports 193 | * rosbuild2 taking shape 194 | * workaround bug #ros3018 until ros-1.2.3 comes out 195 | * removing all the extra exports 196 | * Added Ubuntu platform tags to manifest 197 | * Remove use of deprecated rosbuild macros 198 | * link to tf package as per doc review 199 | * doc reviewed status 200 | * wrapping manifest nicely 201 | * updated url and description 202 | * full migration rules 203 | * switching TransformStamped logic to follow that of all other frame_ids where the frame_id is the operating frame and there is now a child_frame_id which defines the target frame. And the parent frame is gone. This is only changing the message. The API change will come later. 204 | * making covariance follow same convention as Pose 205 | * rotation representation was specified the wrong way in the message comment 206 | * Adding a stamped version of polygon 207 | * Adding comment to Polygon message 208 | * Adding migration rule from ParticleCloud to PoseArray 209 | * clearing API reviews for they've been through a bunch of them recently. 210 | * comments on all msgs except Polygon 211 | * removing PoseWithRates as it's deprecated. 212 | * Changing naming of bag migration rules. 213 | * Modifying migration rules for Odometry and WrenchStamped change of field names. 214 | * Adding actual migration rules for all of the tested common_msgs migrations. 215 | * undo of `#2270 `_, (.data for stamped). reverts r21133 216 | * Adding migration rules to get migration tests to pass. 217 | * switching from PosewithRatesStamped to Odometry `#2277 `_ 218 | * Fixing some of the migration rules associated with unrolling of the .data change. 219 | * PoseWithCovarianceStamped::data -> PoseWithCovarianceStamped::pose 220 | * Reverse r21134, PointStamped::point->PointStamped::data 221 | * reverse QuaternionStamped::quaternion -> QuaternionStamped::data change 222 | * undoing r21137, keeping Vector3Stamped as was, but keeping in fix to door_handle_detector 'using' bug 223 | * Adding more migration rule tests and fixing assorted rules. 224 | * reverting r2118. Redoing `#2275 `_ `#2274 `_ to not go to 'data' standard 225 | * `#2271 `_ Vector3Stamped uses new standarization 226 | * PointStamped::point -> PointStamped::data (`#2276 `_) 227 | * new Stamped format `#2270 `_ 228 | * Changing migration rule for Twist to go to TwistStamped. 229 | * QuaternionStamped::quaternion -> QuaternionStamped::data (`#2278 `_) 230 | * `#2274 `_ `#2275 `_ updated to header/data 231 | * PoseWithCovariance->PoseWithCovarianceStamped 232 | PoseWithCovarianceStamped::pose_with_covariance -> PoseWithCovarianceStamped::data 233 | * First half of the change from deprecated_msgs::RobotBase2DOdom to nav_msgs::Odometry, I think all the c++ compiles, can't speak for functionality yet, also... the python has yet to be run... this may break some things 234 | * Moved robot_msgs/Polygon3D to geometry_msgs/Polygon for ticket `#1310 `_ 235 | * moving PoseArray into geometry_msgs `#1907 `_ 236 | * removing header for this is a type for composing and doesn't stand on it's own to be transformed etc. 237 | * adding TwistWithCovariance `#2251 `_ 238 | * creating Wrench and WrenchStamped in geometry_msgs `#1935 `_ 239 | * adding unused Pose2D message as per API review `#2249 `_ 240 | * geometry_msgs: Documented that covariance uses fixed axis not euler angles. 241 | * merging in the changes to messages see ros-users email. THis is about half the common_msgs API changes 242 | -------------------------------------------------------------------------------- /geometry_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(geometry_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS message_generation std_msgs) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | Accel.msg 10 | AccelStamped.msg 11 | AccelWithCovariance.msg 12 | AccelWithCovarianceStamped.msg 13 | Inertia.msg 14 | InertiaStamped.msg 15 | Point.msg 16 | Point32.msg 17 | PointStamped.msg 18 | Polygon.msg 19 | PolygonStamped.msg 20 | Pose2D.msg 21 | Pose.msg 22 | PoseArray.msg 23 | PoseStamped.msg 24 | PoseWithCovariance.msg 25 | PoseWithCovarianceStamped.msg 26 | Quaternion.msg 27 | QuaternionStamped.msg 28 | Transform.msg 29 | TransformStamped.msg 30 | Twist.msg 31 | TwistStamped.msg 32 | TwistWithCovariance.msg 33 | TwistWithCovarianceStamped.msg 34 | Vector3.msg 35 | Vector3Stamped.msg 36 | Wrench.msg 37 | WrenchStamped.msg) 38 | 39 | generate_messages(DEPENDENCIES std_msgs) 40 | 41 | catkin_package(CATKIN_DEPENDS message_runtime std_msgs) 42 | -------------------------------------------------------------------------------- /geometry_msgs/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | \b geometry_msgs is ... 6 | 7 | 14 | 15 | 16 | \section codeapi Code API 17 | 18 | 28 | 29 | \section rosapi ROS API 30 | 31 | 42 | 43 | 89 | 90 | 91 | 118 | 119 | */ -------------------------------------------------------------------------------- /geometry_msgs/msg/Accel.msg: -------------------------------------------------------------------------------- 1 | # This expresses acceleration in free space broken into its linear and angular parts. 2 | Vector3 linear 3 | Vector3 angular 4 | -------------------------------------------------------------------------------- /geometry_msgs/msg/AccelStamped.msg: -------------------------------------------------------------------------------- 1 | # An accel with reference coordinate frame and timestamp 2 | Header header 3 | Accel accel 4 | -------------------------------------------------------------------------------- /geometry_msgs/msg/AccelWithCovariance.msg: -------------------------------------------------------------------------------- 1 | # This expresses acceleration in free space with uncertainty. 2 | 3 | Accel accel 4 | 5 | # Row-major representation of the 6x6 covariance matrix 6 | # The orientation parameters use a fixed-axis representation. 7 | # In order, the parameters are: 8 | # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) 9 | float64[36] covariance 10 | -------------------------------------------------------------------------------- /geometry_msgs/msg/AccelWithCovarianceStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents an estimated accel with reference coordinate frame and timestamp. 2 | Header header 3 | AccelWithCovariance accel 4 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Inertia.msg: -------------------------------------------------------------------------------- 1 | # Mass [kg] 2 | float64 m 3 | 4 | # Center of mass [m] 5 | geometry_msgs/Vector3 com 6 | 7 | # Inertia Tensor [kg-m^2] 8 | # | ixx ixy ixz | 9 | # I = | ixy iyy iyz | 10 | # | ixz iyz izz | 11 | float64 ixx 12 | float64 ixy 13 | float64 ixz 14 | float64 iyy 15 | float64 iyz 16 | float64 izz 17 | -------------------------------------------------------------------------------- /geometry_msgs/msg/InertiaStamped.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | Inertia inertia 3 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Point.msg: -------------------------------------------------------------------------------- 1 | # This contains the position of a point in free space 2 | float64 x 3 | float64 y 4 | float64 z 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Point32.msg: -------------------------------------------------------------------------------- 1 | # This contains the position of a point in free space(with 32 bits of precision). 2 | # It is recommeded to use Point wherever possible instead of Point32. 3 | # 4 | # This recommendation is to promote interoperability. 5 | # 6 | # This message is designed to take up less space when sending 7 | # lots of points at once, as in the case of a PointCloud. 8 | 9 | float32 x 10 | float32 y 11 | float32 z -------------------------------------------------------------------------------- /geometry_msgs/msg/PointStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents a Point with reference coordinate frame and timestamp 2 | Header header 3 | Point point 4 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Polygon.msg: -------------------------------------------------------------------------------- 1 | #A specification of a polygon where the first and last points are assumed to be connected 2 | Point32[] points 3 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PolygonStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents a Polygon with reference coordinate frame and timestamp 2 | Header header 3 | Polygon polygon 4 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Pose.msg: -------------------------------------------------------------------------------- 1 | # A representation of pose in free space, composed of position and orientation. 2 | Point position 3 | Quaternion orientation 4 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Pose2D.msg: -------------------------------------------------------------------------------- 1 | # Deprecated 2 | # Please use the full 3D pose. 3 | 4 | # In general our recommendation is to use a full 3D representation of everything and for 2D specific applications make the appropriate projections into the plane for their calculations but optimally will preserve the 3D information during processing. 5 | 6 | # If we have parallel copies of 2D datatypes every UI and other pipeline will end up needing to have dual interfaces to plot everything. And you will end up with not being able to use 3D tools for 2D use cases even if they're completely valid, as you'd have to reimplement it with different inputs and outputs. It's not particularly hard to plot the 2D pose or compute the yaw error for the Pose message and there are already tools and libraries that can do this for you. 7 | 8 | 9 | # This expresses a position and orientation on a 2D manifold. 10 | 11 | float64 x 12 | float64 y 13 | float64 theta 14 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PoseArray.msg: -------------------------------------------------------------------------------- 1 | # An array of poses with a header for global reference. 2 | 3 | Header header 4 | 5 | Pose[] poses 6 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PoseStamped.msg: -------------------------------------------------------------------------------- 1 | # A Pose with reference coordinate frame and timestamp 2 | Header header 3 | Pose pose 4 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PoseWithCovariance.msg: -------------------------------------------------------------------------------- 1 | # This represents a pose in free space with uncertainty. 2 | 3 | Pose pose 4 | 5 | # Row-major representation of the 6x6 covariance matrix 6 | # The orientation parameters use a fixed-axis representation. 7 | # In order, the parameters are: 8 | # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) 9 | float64[36] covariance 10 | -------------------------------------------------------------------------------- /geometry_msgs/msg/PoseWithCovarianceStamped.msg: -------------------------------------------------------------------------------- 1 | # This expresses an estimated pose with a reference coordinate frame and timestamp 2 | 3 | Header header 4 | PoseWithCovariance pose 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Quaternion.msg: -------------------------------------------------------------------------------- 1 | # This represents an orientation in free space in quaternion form. 2 | 3 | float64 x 4 | float64 y 5 | float64 z 6 | float64 w 7 | -------------------------------------------------------------------------------- /geometry_msgs/msg/QuaternionStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents an orientation with reference coordinate frame and timestamp. 2 | 3 | Header header 4 | Quaternion quaternion 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Transform.msg: -------------------------------------------------------------------------------- 1 | # This represents the transform between two coordinate frames in free space. 2 | 3 | Vector3 translation 4 | Quaternion rotation 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/TransformStamped.msg: -------------------------------------------------------------------------------- 1 | # This expresses a transform from coordinate frame header.frame_id 2 | # to the coordinate frame child_frame_id 3 | # 4 | # This message is mostly used by the 5 | # tf package. 6 | # See its documentation for more information. 7 | 8 | Header header 9 | string child_frame_id # the frame id of the child frame 10 | Transform transform 11 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Twist.msg: -------------------------------------------------------------------------------- 1 | # This expresses velocity in free space broken into its linear and angular parts. 2 | Vector3 linear 3 | Vector3 angular 4 | -------------------------------------------------------------------------------- /geometry_msgs/msg/TwistStamped.msg: -------------------------------------------------------------------------------- 1 | # A twist with reference coordinate frame and timestamp 2 | Header header 3 | Twist twist 4 | -------------------------------------------------------------------------------- /geometry_msgs/msg/TwistWithCovariance.msg: -------------------------------------------------------------------------------- 1 | # This expresses velocity in free space with uncertainty. 2 | 3 | Twist twist 4 | 5 | # Row-major representation of the 6x6 covariance matrix 6 | # The orientation parameters use a fixed-axis representation. 7 | # In order, the parameters are: 8 | # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) 9 | float64[36] covariance 10 | -------------------------------------------------------------------------------- /geometry_msgs/msg/TwistWithCovarianceStamped.msg: -------------------------------------------------------------------------------- 1 | # This represents an estimated twist with reference coordinate frame and timestamp. 2 | Header header 3 | TwistWithCovariance twist 4 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Vector3.msg: -------------------------------------------------------------------------------- 1 | # This represents a vector in free space. 2 | # It is only meant to represent a direction. Therefore, it does not 3 | # make sense to apply a translation to it (e.g., when applying a 4 | # generic rigid transformation to a Vector3, tf2 will only apply the 5 | # rotation). If you want your data to be translatable too, use the 6 | # geometry_msgs/Point message instead. 7 | 8 | float64 x 9 | float64 y 10 | float64 z -------------------------------------------------------------------------------- /geometry_msgs/msg/Vector3Stamped.msg: -------------------------------------------------------------------------------- 1 | # This represents a Vector3 with reference coordinate frame and timestamp 2 | Header header 3 | Vector3 vector 4 | -------------------------------------------------------------------------------- /geometry_msgs/msg/Wrench.msg: -------------------------------------------------------------------------------- 1 | # This represents force in free space, separated into 2 | # its linear and angular parts. 3 | Vector3 force 4 | Vector3 torque 5 | -------------------------------------------------------------------------------- /geometry_msgs/msg/WrenchStamped.msg: -------------------------------------------------------------------------------- 1 | # A wrench with reference coordinate frame and timestamp 2 | Header header 3 | Wrench wrench 4 | -------------------------------------------------------------------------------- /geometry_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | geometry_msgs 3 | 1.13.2 4 | 5 | geometry_msgs provides messages for common geometric primitives 6 | such as points, vectors, and poses. These primitives are designed 7 | to provide a common data type and facilitate interoperability 8 | throughout the system. 9 | 10 | Michel Hidalgo 11 | BSD 12 | 13 | http://wiki.ros.org/geometry_msgs 14 | Tully Foote 15 | 16 | catkin 17 | 18 | message_generation 19 | std_msgs 20 | 21 | message_runtime 22 | std_msgs 23 | 24 | 25 | 26 | 27 | 28 | -------------------------------------------------------------------------------- /nav_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(nav_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation std_msgs actionlib_msgs) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | GridCells.msg 10 | MapMetaData.msg 11 | OccupancyGrid.msg 12 | Odometry.msg 13 | Path.msg) 14 | 15 | add_service_files( 16 | DIRECTORY srv 17 | FILES 18 | GetMap.srv 19 | GetPlan.srv 20 | SetMap.srv 21 | LoadMap.srv) 22 | 23 | add_action_files( 24 | FILES 25 | GetMap.action) 26 | 27 | generate_messages(DEPENDENCIES geometry_msgs std_msgs actionlib_msgs) 28 | 29 | catkin_package(CATKIN_DEPENDS geometry_msgs message_runtime std_msgs actionlib_msgs) 30 | -------------------------------------------------------------------------------- /nav_msgs/action/GetMap.action: -------------------------------------------------------------------------------- 1 | # Get the map as a nav_msgs/OccupancyGrid 2 | --- 3 | nav_msgs/OccupancyGrid map 4 | --- 5 | # no feedback -------------------------------------------------------------------------------- /nav_msgs/msg/GridCells.msg: -------------------------------------------------------------------------------- 1 | #an array of cells in a 2D grid 2 | Header header 3 | float32 cell_width 4 | float32 cell_height 5 | geometry_msgs/Point[] cells 6 | -------------------------------------------------------------------------------- /nav_msgs/msg/MapMetaData.msg: -------------------------------------------------------------------------------- 1 | # This hold basic information about the characterists of the OccupancyGrid 2 | 3 | # The time at which the map was loaded 4 | time map_load_time 5 | # The map resolution [m/cell] 6 | float32 resolution 7 | # Map width [cells] 8 | uint32 width 9 | # Map height [cells] 10 | uint32 height 11 | # The origin of the map [m, m, rad]. This is the real-world pose of the 12 | # cell (0,0) in the map. 13 | geometry_msgs/Pose origin -------------------------------------------------------------------------------- /nav_msgs/msg/OccupancyGrid.msg: -------------------------------------------------------------------------------- 1 | # This represents a 2-D grid map, in which each cell represents the probability of 2 | # occupancy. 3 | 4 | Header header 5 | 6 | #MetaData for the map 7 | MapMetaData info 8 | 9 | # The map data, in row-major order, starting with (0,0). Occupancy 10 | # probabilities are in the range [0,100]. Unknown is -1. 11 | int8[] data 12 | -------------------------------------------------------------------------------- /nav_msgs/msg/Odometry.msg: -------------------------------------------------------------------------------- 1 | # This represents an estimate of a position and velocity in free space. 2 | # The pose in this message should be specified in the coordinate frame given by header.frame_id. 3 | # The twist in this message should be specified in the coordinate frame given by the child_frame_id 4 | Header header 5 | string child_frame_id 6 | geometry_msgs/PoseWithCovariance pose 7 | geometry_msgs/TwistWithCovariance twist 8 | -------------------------------------------------------------------------------- /nav_msgs/msg/Path.msg: -------------------------------------------------------------------------------- 1 | #An array of poses that represents a Path for a robot to follow 2 | Header header 3 | geometry_msgs/PoseStamped[] poses 4 | -------------------------------------------------------------------------------- /nav_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | nav_msgs 3 | 1.13.2 4 | 5 | nav_msgs defines the common messages used to interact with the 6 | navigation stack. 7 | 8 | Michel Hidalgo 9 | BSD 10 | 11 | http://wiki.ros.org/nav_msgs 12 | Tully Foote 13 | 14 | catkin 15 | 16 | geometry_msgs 17 | message_generation 18 | std_msgs 19 | actionlib_msgs 20 | 21 | geometry_msgs 22 | message_runtime 23 | std_msgs 24 | actionlib_msgs 25 | 26 | 27 | 28 | 29 | 30 | -------------------------------------------------------------------------------- /nav_msgs/srv/GetMap.srv: -------------------------------------------------------------------------------- 1 | # Get the map as a nav_msgs/OccupancyGrid 2 | --- 3 | nav_msgs/OccupancyGrid map 4 | -------------------------------------------------------------------------------- /nav_msgs/srv/GetPlan.srv: -------------------------------------------------------------------------------- 1 | # Get a plan from the current position to the goal Pose 2 | 3 | # The start pose for the plan 4 | geometry_msgs/PoseStamped start 5 | 6 | # The final pose of the goal position 7 | geometry_msgs/PoseStamped goal 8 | 9 | # If the goal is obstructed, how many meters the planner can 10 | # relax the constraint in x and y before failing. 11 | float32 tolerance 12 | --- 13 | nav_msgs/Path plan 14 | -------------------------------------------------------------------------------- /nav_msgs/srv/LoadMap.srv: -------------------------------------------------------------------------------- 1 | # URL of map resource 2 | # Can be an absolute path to a file: file:///path/to/maps/floor1.yaml 3 | # Or, relative to a ROS package: package://my_ros_package/maps/floor2.yaml 4 | string map_url 5 | --- 6 | # Result code defintions 7 | uint8 RESULT_SUCCESS=0 8 | uint8 RESULT_MAP_DOES_NOT_EXIST=1 9 | uint8 RESULT_INVALID_MAP_DATA=2 10 | uint8 RESULT_INVALID_MAP_METADATA=3 11 | uint8 RESULT_UNDEFINED_FAILURE=255 12 | 13 | # Returned map is only valid if result equals RESULT_SUCCESS 14 | nav_msgs/OccupancyGrid map 15 | uint8 result 16 | -------------------------------------------------------------------------------- /nav_msgs/srv/SetMap.srv: -------------------------------------------------------------------------------- 1 | # Set a new map together with an initial pose 2 | nav_msgs/OccupancyGrid map 3 | geometry_msgs/PoseWithCovarianceStamped initial_pose 4 | --- 5 | bool success 6 | 7 | -------------------------------------------------------------------------------- /sensor_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(sensor_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation std_msgs) 5 | 6 | # For point_cloud2.py 7 | catkin_python_setup() 8 | 9 | include_directories(include) 10 | 11 | add_message_files( 12 | DIRECTORY msg 13 | FILES 14 | BatteryState.msg 15 | CameraInfo.msg 16 | ChannelFloat32.msg 17 | CompressedImage.msg 18 | FluidPressure.msg 19 | Illuminance.msg 20 | Image.msg 21 | Imu.msg 22 | JointState.msg 23 | Joy.msg 24 | JoyFeedback.msg 25 | JoyFeedbackArray.msg 26 | LaserEcho.msg 27 | LaserScan.msg 28 | MagneticField.msg 29 | MultiDOFJointState.msg 30 | MultiEchoLaserScan.msg 31 | NavSatFix.msg 32 | NavSatStatus.msg 33 | PointCloud.msg 34 | PointCloud2.msg 35 | PointField.msg 36 | Range.msg 37 | RegionOfInterest.msg 38 | RelativeHumidity.msg 39 | Temperature.msg 40 | TimeReference.msg) 41 | 42 | add_service_files( 43 | DIRECTORY srv 44 | FILES SetCameraInfo.srv) 45 | 46 | generate_messages(DEPENDENCIES geometry_msgs std_msgs) 47 | 48 | catkin_package( 49 | INCLUDE_DIRS include 50 | CATKIN_DEPENDS geometry_msgs message_runtime std_msgs) 51 | 52 | install(DIRECTORY include/${PROJECT_NAME}/ 53 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 54 | FILES_MATCHING PATTERN "*.h") 55 | 56 | install(DIRECTORY migration_rules 57 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 58 | 59 | if (CATKIN_ENABLE_TESTING) 60 | add_subdirectory(test) 61 | endif() 62 | -------------------------------------------------------------------------------- /sensor_msgs/include/sensor_msgs/distortion_models.h: -------------------------------------------------------------------------------- 1 | 2 | /********************************************************************* 3 | * Software License Agreement (BSD License) 4 | * 5 | * Copyright (c) 2010, Willow Garage, Inc. 6 | * All rights reserved. 7 | * 8 | * Redistribution and use in source and binary forms, with or without 9 | * modification, are permitted provided that the following conditions 10 | * are met: 11 | * 12 | * * Redistributions of source code must retain the above copyright 13 | * notice, this list of conditions and the following disclaimer. 14 | * * Redistributions in binary form must reproduce the above 15 | * copyright notice, this list of conditions and the following 16 | * disclaimer in the documentation and/or other materials provided 17 | * with the distribution. 18 | * * Neither the name of the Willow Garage nor the names of its 19 | * contributors may be used to endorse or promote products derived 20 | * from this software without specific prior written permission. 21 | * 22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 33 | * POSSIBILITY OF SUCH DAMAGE. 34 | *********************************************************************/ 35 | 36 | #ifndef SENSOR_MSGS_DISTORTION_MODELS_H 37 | #define SENSOR_MSGS_DISTORTION_MODELS_H 38 | 39 | #include 40 | 41 | namespace sensor_msgs 42 | { 43 | namespace distortion_models 44 | { 45 | const std::string PLUMB_BOB = "plumb_bob"; 46 | const std::string RATIONAL_POLYNOMIAL = "rational_polynomial"; 47 | const std::string EQUIDISTANT = "equidistant"; 48 | } 49 | } 50 | 51 | #endif 52 | -------------------------------------------------------------------------------- /sensor_msgs/include/sensor_msgs/fill_image.h: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2008, Willow Garage, Inc. 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of the Willow Garage nor the names of its 18 | * contributors may be used to endorse or promote products derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | *********************************************************************/ 34 | 35 | #ifndef FILLIMAGE_HH 36 | #define FILLIMAGE_HH 37 | 38 | #include "sensor_msgs/Image.h" 39 | #include "sensor_msgs/image_encodings.h" 40 | 41 | namespace sensor_msgs 42 | { 43 | 44 | static inline bool fillImage(Image& image, 45 | const std::string& encoding_arg, 46 | uint32_t rows_arg, 47 | uint32_t cols_arg, 48 | uint32_t step_arg, 49 | const void* data_arg) 50 | { 51 | image.encoding = encoding_arg; 52 | image.height = rows_arg; 53 | image.width = cols_arg; 54 | image.step = step_arg; 55 | size_t st0 = (step_arg * rows_arg); 56 | image.data.resize(st0); 57 | memcpy(&image.data[0], data_arg, st0); 58 | 59 | image.is_bigendian = 0; 60 | return true; 61 | } 62 | 63 | static inline void clearImage(Image& image) 64 | { 65 | image.data.resize(0); 66 | } 67 | } 68 | 69 | 70 | #endif 71 | -------------------------------------------------------------------------------- /sensor_msgs/include/sensor_msgs/image_encodings.h: -------------------------------------------------------------------------------- 1 | 2 | /********************************************************************* 3 | * Software License Agreement (BSD License) 4 | * 5 | * Copyright (c) 2009, Willow Garage, Inc. 6 | * All rights reserved. 7 | * 8 | * Redistribution and use in source and binary forms, with or without 9 | * modification, are permitted provided that the following conditions 10 | * are met: 11 | * 12 | * * Redistributions of source code must retain the above copyright 13 | * notice, this list of conditions and the following disclaimer. 14 | * * Redistributions in binary form must reproduce the above 15 | * copyright notice, this list of conditions and the following 16 | * disclaimer in the documentation and/or other materials provided 17 | * with the distribution. 18 | * * Neither the name of the Willow Garage nor the names of its 19 | * contributors may be used to endorse or promote products derived 20 | * from this software without specific prior written permission. 21 | * 22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 33 | * POSSIBILITY OF SUCH DAMAGE. 34 | *********************************************************************/ 35 | 36 | #ifndef SENSOR_MSGS_IMAGE_ENCODINGS_H 37 | #define SENSOR_MSGS_IMAGE_ENCODINGS_H 38 | 39 | #include 40 | #include 41 | #include 42 | 43 | namespace sensor_msgs 44 | { 45 | namespace image_encodings 46 | { 47 | const std::string RGB8 = "rgb8"; 48 | const std::string RGBA8 = "rgba8"; 49 | const std::string RGB16 = "rgb16"; 50 | const std::string RGBA16 = "rgba16"; 51 | const std::string BGR8 = "bgr8"; 52 | const std::string BGRA8 = "bgra8"; 53 | const std::string BGR16 = "bgr16"; 54 | const std::string BGRA16 = "bgra16"; 55 | const std::string MONO8="mono8"; 56 | const std::string MONO16="mono16"; 57 | 58 | // OpenCV CvMat types 59 | const std::string TYPE_8UC1="8UC1"; 60 | const std::string TYPE_8UC2="8UC2"; 61 | const std::string TYPE_8UC3="8UC3"; 62 | const std::string TYPE_8UC4="8UC4"; 63 | const std::string TYPE_8SC1="8SC1"; 64 | const std::string TYPE_8SC2="8SC2"; 65 | const std::string TYPE_8SC3="8SC3"; 66 | const std::string TYPE_8SC4="8SC4"; 67 | const std::string TYPE_16UC1="16UC1"; 68 | const std::string TYPE_16UC2="16UC2"; 69 | const std::string TYPE_16UC3="16UC3"; 70 | const std::string TYPE_16UC4="16UC4"; 71 | const std::string TYPE_16SC1="16SC1"; 72 | const std::string TYPE_16SC2="16SC2"; 73 | const std::string TYPE_16SC3="16SC3"; 74 | const std::string TYPE_16SC4="16SC4"; 75 | const std::string TYPE_32SC1="32SC1"; 76 | const std::string TYPE_32SC2="32SC2"; 77 | const std::string TYPE_32SC3="32SC3"; 78 | const std::string TYPE_32SC4="32SC4"; 79 | const std::string TYPE_32FC1="32FC1"; 80 | const std::string TYPE_32FC2="32FC2"; 81 | const std::string TYPE_32FC3="32FC3"; 82 | const std::string TYPE_32FC4="32FC4"; 83 | const std::string TYPE_64FC1="64FC1"; 84 | const std::string TYPE_64FC2="64FC2"; 85 | const std::string TYPE_64FC3="64FC3"; 86 | const std::string TYPE_64FC4="64FC4"; 87 | 88 | // Bayer encodings 89 | const std::string BAYER_RGGB8="bayer_rggb8"; 90 | const std::string BAYER_BGGR8="bayer_bggr8"; 91 | const std::string BAYER_GBRG8="bayer_gbrg8"; 92 | const std::string BAYER_GRBG8="bayer_grbg8"; 93 | const std::string BAYER_RGGB16="bayer_rggb16"; 94 | const std::string BAYER_BGGR16="bayer_bggr16"; 95 | const std::string BAYER_GBRG16="bayer_gbrg16"; 96 | const std::string BAYER_GRBG16="bayer_grbg16"; 97 | 98 | // Miscellaneous 99 | // This is the UYVY version of YUV422 codec http://www.fourcc.org/yuv.php#UYVY 100 | // with an 8-bit depth 101 | const std::string YUV422="yuv422"; 102 | 103 | // Prefixes for abstract image encodings 104 | const std::string ABSTRACT_ENCODING_PREFIXES[] = { 105 | "8UC", "8SC", "16UC", "16SC", "32SC", "32FC", "64FC"}; 106 | 107 | // Utility functions for inspecting an encoding string 108 | static inline bool isColor(const std::string& encoding) 109 | { 110 | return encoding == RGB8 || encoding == BGR8 || 111 | encoding == RGBA8 || encoding == BGRA8 || 112 | encoding == RGB16 || encoding == BGR16 || 113 | encoding == RGBA16 || encoding == BGRA16; 114 | } 115 | 116 | static inline bool isMono(const std::string& encoding) 117 | { 118 | return encoding == MONO8 || encoding == MONO16; 119 | } 120 | 121 | static inline bool isBayer(const std::string& encoding) 122 | { 123 | return encoding == BAYER_RGGB8 || encoding == BAYER_BGGR8 || 124 | encoding == BAYER_GBRG8 || encoding == BAYER_GRBG8 || 125 | encoding == BAYER_RGGB16 || encoding == BAYER_BGGR16 || 126 | encoding == BAYER_GBRG16 || encoding == BAYER_GRBG16; 127 | } 128 | 129 | static inline bool hasAlpha(const std::string& encoding) 130 | { 131 | return encoding == RGBA8 || encoding == BGRA8 || 132 | encoding == RGBA16 || encoding == BGRA16; 133 | } 134 | 135 | static inline int numChannels(const std::string& encoding) 136 | { 137 | // First do the common-case encodings 138 | if (encoding == MONO8 || 139 | encoding == MONO16) 140 | return 1; 141 | if (encoding == BGR8 || 142 | encoding == RGB8 || 143 | encoding == BGR16 || 144 | encoding == RGB16) 145 | return 3; 146 | if (encoding == BGRA8 || 147 | encoding == RGBA8 || 148 | encoding == BGRA16 || 149 | encoding == RGBA16) 150 | return 4; 151 | if (encoding == BAYER_RGGB8 || 152 | encoding == BAYER_BGGR8 || 153 | encoding == BAYER_GBRG8 || 154 | encoding == BAYER_GRBG8 || 155 | encoding == BAYER_RGGB16 || 156 | encoding == BAYER_BGGR16 || 157 | encoding == BAYER_GBRG16 || 158 | encoding == BAYER_GRBG16) 159 | return 1; 160 | 161 | // Now all the generic content encodings 162 | // TODO: Rewrite with regex when ROS supports C++11 163 | for (size_t i=0; i < sizeof(ABSTRACT_ENCODING_PREFIXES) / sizeof(*ABSTRACT_ENCODING_PREFIXES); i++) 164 | { 165 | std::string prefix = ABSTRACT_ENCODING_PREFIXES[i]; 166 | if (encoding.substr(0, prefix.size()) != prefix) 167 | continue; 168 | if (encoding.size() == prefix.size()) 169 | return 1; // ex. 8UC -> 1 170 | int n_channel = atoi(encoding.substr(prefix.size(), 171 | encoding.size() - prefix.size()).c_str()); // ex. 8UC5 -> 5 172 | if (n_channel != 0) 173 | return n_channel; // valid encoding string 174 | } 175 | 176 | if (encoding == YUV422) 177 | return 2; 178 | 179 | throw std::runtime_error("Unknown encoding " + encoding); 180 | return -1; 181 | } 182 | 183 | static inline int bitDepth(const std::string& encoding) 184 | { 185 | if (encoding == MONO16) 186 | return 16; 187 | if (encoding == MONO8 || 188 | encoding == BGR8 || 189 | encoding == RGB8 || 190 | encoding == BGRA8 || 191 | encoding == RGBA8 || 192 | encoding == BAYER_RGGB8 || 193 | encoding == BAYER_BGGR8 || 194 | encoding == BAYER_GBRG8 || 195 | encoding == BAYER_GRBG8) 196 | return 8; 197 | 198 | if (encoding == MONO16 || 199 | encoding == BGR16 || 200 | encoding == RGB16 || 201 | encoding == BGRA16 || 202 | encoding == RGBA16 || 203 | encoding == BAYER_RGGB16 || 204 | encoding == BAYER_BGGR16 || 205 | encoding == BAYER_GBRG16 || 206 | encoding == BAYER_GRBG16) 207 | return 16; 208 | 209 | // Now all the generic content encodings 210 | // TODO: Rewrite with regex when ROS supports C++11 211 | for (size_t i=0; i < sizeof(ABSTRACT_ENCODING_PREFIXES) / sizeof(*ABSTRACT_ENCODING_PREFIXES); i++) 212 | { 213 | std::string prefix = ABSTRACT_ENCODING_PREFIXES[i]; 214 | if (encoding.substr(0, prefix.size()) != prefix) 215 | continue; 216 | if (encoding.size() == prefix.size()) 217 | return atoi(prefix.c_str()); // ex. 8UC -> 8 218 | int n_channel = atoi(encoding.substr(prefix.size(), 219 | encoding.size() - prefix.size()).c_str()); // ex. 8UC10 -> 10 220 | if (n_channel != 0) 221 | return atoi(prefix.c_str()); // valid encoding string 222 | } 223 | 224 | if (encoding == YUV422) 225 | return 8; 226 | 227 | throw std::runtime_error("Unknown encoding " + encoding); 228 | return -1; 229 | } 230 | } 231 | } 232 | 233 | #endif 234 | -------------------------------------------------------------------------------- /sensor_msgs/include/sensor_msgs/point_cloud_conversion.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2010, Willow Garage, Inc. 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of Willow Garage, Inc. nor the names of its 18 | * contributors may be used to endorse or promote products derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | * 34 | * $Id$ 35 | * 36 | */ 37 | 38 | #ifndef SENSOR_MSGS_POINT_CLOUD_CONVERSION_H 39 | #define SENSOR_MSGS_POINT_CLOUD_CONVERSION_H 40 | 41 | #include 42 | #include 43 | #include 44 | 45 | /** 46 | * \brief Convert between the old (sensor_msgs::PointCloud) and the new (sensor_msgs::PointCloud2) format. 47 | * \author Radu Bogdan Rusu 48 | */ 49 | namespace sensor_msgs 50 | { 51 | ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// 52 | /** \brief Get the index of a specified field (i.e., dimension/channel) 53 | * \param points the the point cloud message 54 | * \param field_name the string defining the field name 55 | */ 56 | static inline int getPointCloud2FieldIndex (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name) 57 | { 58 | // Get the index we need 59 | for (size_t d = 0; d < cloud.fields.size (); ++d) 60 | if (cloud.fields[d].name == field_name) 61 | return (d); 62 | return (-1); 63 | } 64 | 65 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// 66 | /** \brief Convert a sensor_msgs::PointCloud message to a sensor_msgs::PointCloud2 message. 67 | * \param input the message in the sensor_msgs::PointCloud format 68 | * \param output the resultant message in the sensor_msgs::PointCloud2 format 69 | */ 70 | static inline bool convertPointCloudToPointCloud2 (const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output) 71 | { 72 | output.header = input.header; 73 | output.width = input.points.size (); 74 | output.height = 1; 75 | output.fields.resize (3 + input.channels.size ()); 76 | // Convert x/y/z to fields 77 | output.fields[0].name = "x"; output.fields[1].name = "y"; output.fields[2].name = "z"; 78 | int offset = 0; 79 | // All offsets are *4, as all field data types are float32 80 | for (size_t d = 0; d < output.fields.size (); ++d, offset += 4) 81 | { 82 | output.fields[d].offset = offset; 83 | output.fields[d].datatype = sensor_msgs::PointField::FLOAT32; 84 | output.fields[d].count = 1; 85 | } 86 | output.point_step = offset; 87 | output.row_step = output.point_step * output.width; 88 | // Convert the remaining of the channels to fields 89 | for (size_t d = 0; d < input.channels.size (); ++d) 90 | output.fields[3 + d].name = input.channels[d].name; 91 | output.data.resize (input.points.size () * output.point_step); 92 | output.is_bigendian = false; // @todo ? 93 | output.is_dense = false; 94 | 95 | // Copy the data points 96 | for (size_t cp = 0; cp < input.points.size (); ++cp) 97 | { 98 | memcpy (&output.data[cp * output.point_step + output.fields[0].offset], &input.points[cp].x, sizeof (float)); 99 | memcpy (&output.data[cp * output.point_step + output.fields[1].offset], &input.points[cp].y, sizeof (float)); 100 | memcpy (&output.data[cp * output.point_step + output.fields[2].offset], &input.points[cp].z, sizeof (float)); 101 | for (size_t d = 0; d < input.channels.size (); ++d) 102 | { 103 | if (input.channels[d].values.size() == input.points.size()) 104 | { 105 | memcpy (&output.data[cp * output.point_step + output.fields[3 + d].offset], &input.channels[d].values[cp], sizeof (float)); 106 | } 107 | } 108 | } 109 | return (true); 110 | } 111 | 112 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// 113 | /** \brief Convert a sensor_msgs::PointCloud2 message to a sensor_msgs::PointCloud message. 114 | * \param input the message in the sensor_msgs::PointCloud2 format 115 | * \param output the resultant message in the sensor_msgs::PointCloud format 116 | */ 117 | static inline bool convertPointCloud2ToPointCloud (const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud &output) 118 | { 119 | 120 | output.header = input.header; 121 | output.points.resize (input.width * input.height); 122 | output.channels.resize (input.fields.size () - 3); 123 | // Get the x/y/z field offsets 124 | int x_idx = getPointCloud2FieldIndex (input, "x"); 125 | int y_idx = getPointCloud2FieldIndex (input, "y"); 126 | int z_idx = getPointCloud2FieldIndex (input, "z"); 127 | if (x_idx == -1 || y_idx == -1 || z_idx == -1) 128 | { 129 | std::cerr << "x/y/z coordinates not found! Cannot convert to sensor_msgs::PointCloud!" << std::endl; 130 | return (false); 131 | } 132 | int x_offset = input.fields[x_idx].offset; 133 | int y_offset = input.fields[y_idx].offset; 134 | int z_offset = input.fields[z_idx].offset; 135 | uint8_t x_datatype = input.fields[x_idx].datatype; 136 | uint8_t y_datatype = input.fields[y_idx].datatype; 137 | uint8_t z_datatype = input.fields[z_idx].datatype; 138 | 139 | // Convert the fields to channels 140 | int cur_c = 0; 141 | for (size_t d = 0; d < input.fields.size (); ++d) 142 | { 143 | if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset) 144 | continue; 145 | output.channels[cur_c].name = input.fields[d].name; 146 | output.channels[cur_c].values.resize (output.points.size ()); 147 | cur_c++; 148 | } 149 | 150 | // Copy the data points 151 | for (size_t cp = 0; cp < output.points.size (); ++cp) 152 | { 153 | // Copy x/y/z 154 | output.points[cp].x = sensor_msgs::readPointCloud2BufferValue(&input.data[cp * input.point_step + x_offset], x_datatype); 155 | output.points[cp].y = sensor_msgs::readPointCloud2BufferValue(&input.data[cp * input.point_step + y_offset], y_datatype); 156 | output.points[cp].z = sensor_msgs::readPointCloud2BufferValue(&input.data[cp * input.point_step + z_offset], z_datatype); 157 | // Copy the rest of the data 158 | int cur_c = 0; 159 | for (size_t d = 0; d < input.fields.size (); ++d) 160 | { 161 | if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset) 162 | continue; 163 | output.channels[cur_c++].values[cp] = sensor_msgs::readPointCloud2BufferValue(&input.data[cp * input.point_step + input.fields[d].offset], input.fields[d].datatype); 164 | } 165 | } 166 | return (true); 167 | } 168 | } 169 | #endif// SENSOR_MSGS_POINT_CLOUD_CONVERSION_H 170 | -------------------------------------------------------------------------------- /sensor_msgs/include/sensor_msgs/point_field_conversion.h: -------------------------------------------------------------------------------- 1 | /* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Robot Operating System code by the University of Osnabrück 5 | * Copyright (c) 2015, University of Osnabrück 6 | * All rights reserved. 7 | * 8 | * Redistribution and use in source and binary forms, with or without 9 | * modification, are permitted provided that the following conditions 10 | * are met: 11 | * 12 | * 1. Redistributions of source code must retain the above 13 | * copyright notice, this list of conditions and the following 14 | * disclaimer. 15 | * 16 | * 2. Redistributions in binary form must reproduce the above 17 | * copyright notice, this list of conditions and the following 18 | * disclaimer in the documentation and/or other materials provided 19 | * with the distribution. 20 | * 21 | * 3. Neither the name of the copyright holder nor the names of its 22 | * contributors may be used to endorse or promote products derived 23 | * from this software without specific prior written permission. 24 | * 25 | * 26 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 27 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED 28 | * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 29 | * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR 30 | * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, 31 | * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, 32 | * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; 33 | * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, 34 | * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR 35 | * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF 36 | * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 37 | * 38 | * 39 | * 40 | * point_field_conversion.h 41 | * 42 | * Created on: 16.07.2015 43 | * Authors: Sebastian Pütz 44 | */ 45 | 46 | #ifndef SENSOR_MSGS_POINT_FIELD_CONVERSION_H 47 | #define SENSOR_MSGS_POINT_FIELD_CONVERSION_H 48 | 49 | /** 50 | * \brief This file provides a type to enum mapping for the different 51 | * PointField types and methods to read and write in 52 | * a PointCloud2 buffer for the different PointField types. 53 | * \author Sebastian Pütz 54 | */ 55 | namespace sensor_msgs{ 56 | /*! 57 | * \Enum to type mapping. 58 | */ 59 | template struct pointFieldTypeAsType {}; 60 | template<> struct pointFieldTypeAsType { typedef int8_t type; }; 61 | template<> struct pointFieldTypeAsType { typedef uint8_t type; }; 62 | template<> struct pointFieldTypeAsType { typedef int16_t type; }; 63 | template<> struct pointFieldTypeAsType { typedef uint16_t type; }; 64 | template<> struct pointFieldTypeAsType { typedef int32_t type; }; 65 | template<> struct pointFieldTypeAsType { typedef uint32_t type; }; 66 | template<> struct pointFieldTypeAsType { typedef float type; }; 67 | template<> struct pointFieldTypeAsType { typedef double type; }; 68 | 69 | /*! 70 | * \Type to enum mapping. 71 | */ 72 | template struct typeAsPointFieldType {}; 73 | template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::INT8; }; 74 | template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::UINT8; }; 75 | template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::INT16; }; 76 | template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::UINT16; }; 77 | template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::INT32; }; 78 | template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::UINT32; }; 79 | template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::FLOAT32; }; 80 | template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::FLOAT64; }; 81 | 82 | /*! 83 | * \Converts a value at the given pointer position, interpreted as the datatype 84 | * specified by the given template argument point_field_type, to the given 85 | * template type T and returns it. 86 | * \param data_ptr pointer into the point cloud 2 buffer 87 | * \tparam point_field_type sensor_msgs::PointField datatype value 88 | * \tparam T return type 89 | */ 90 | template 91 | inline T readPointCloud2BufferValue(const unsigned char* data_ptr){ 92 | typedef typename pointFieldTypeAsType::type type; 93 | return static_cast(*(reinterpret_cast(data_ptr))); 94 | } 95 | 96 | /*! 97 | * \Converts a value at the given pointer position interpreted as the datatype 98 | * specified by the given datatype parameter to the given template type and returns it. 99 | * \param data_ptr pointer into the point cloud 2 buffer 100 | * \param datatype sensor_msgs::PointField datatype value 101 | * \tparam T return type 102 | */ 103 | template 104 | inline T readPointCloud2BufferValue(const unsigned char* data_ptr, const unsigned char datatype){ 105 | switch(datatype){ 106 | case sensor_msgs::PointField::INT8: 107 | return readPointCloud2BufferValue(data_ptr); 108 | case sensor_msgs::PointField::UINT8: 109 | return readPointCloud2BufferValue(data_ptr); 110 | case sensor_msgs::PointField::INT16: 111 | return readPointCloud2BufferValue(data_ptr); 112 | case sensor_msgs::PointField::UINT16: 113 | return readPointCloud2BufferValue(data_ptr); 114 | case sensor_msgs::PointField::INT32: 115 | return readPointCloud2BufferValue(data_ptr); 116 | case sensor_msgs::PointField::UINT32: 117 | return readPointCloud2BufferValue(data_ptr); 118 | case sensor_msgs::PointField::FLOAT32: 119 | return readPointCloud2BufferValue(data_ptr); 120 | case sensor_msgs::PointField::FLOAT64: 121 | return readPointCloud2BufferValue(data_ptr); 122 | } 123 | // This should never be reached, but return statement added to avoid compiler warning. (#84) 124 | return T(); 125 | } 126 | 127 | /*! 128 | * \Inserts a given value at the given point position interpreted as the datatype 129 | * specified by the template argument point_field_type. 130 | * \param data_ptr pointer into the point cloud 2 buffer 131 | * \param value the value to insert 132 | * \tparam point_field_type sensor_msgs::PointField datatype value 133 | * \tparam T type of the value to insert 134 | */ 135 | template 136 | inline void writePointCloud2BufferValue(unsigned char* data_ptr, T value){ 137 | typedef typename pointFieldTypeAsType::type type; 138 | *(reinterpret_cast(data_ptr)) = static_cast(value); 139 | } 140 | 141 | /*! 142 | * \Inserts a given value at the given point position interpreted as the datatype 143 | * specified by the given datatype parameter. 144 | * \param data_ptr pointer into the point cloud 2 buffer 145 | * \param datatype sensor_msgs::PointField datatype value 146 | * \param value the value to insert 147 | * \tparam T type of the value to insert 148 | */ 149 | template 150 | inline void writePointCloud2BufferValue(unsigned char* data_ptr, const unsigned char datatype, T value){ 151 | switch(datatype){ 152 | case sensor_msgs::PointField::INT8: 153 | writePointCloud2BufferValue(data_ptr, value); 154 | break; 155 | case sensor_msgs::PointField::UINT8: 156 | writePointCloud2BufferValue(data_ptr, value); 157 | break; 158 | case sensor_msgs::PointField::INT16: 159 | writePointCloud2BufferValue(data_ptr, value); 160 | break; 161 | case sensor_msgs::PointField::UINT16: 162 | writePointCloud2BufferValue(data_ptr, value); 163 | break; 164 | case sensor_msgs::PointField::INT32: 165 | writePointCloud2BufferValue(data_ptr, value); 166 | break; 167 | case sensor_msgs::PointField::UINT32: 168 | writePointCloud2BufferValue(data_ptr, value); 169 | break; 170 | case sensor_msgs::PointField::FLOAT32: 171 | writePointCloud2BufferValue(data_ptr, value); 172 | break; 173 | case sensor_msgs::PointField::FLOAT64: 174 | writePointCloud2BufferValue(data_ptr, value); 175 | break; 176 | } 177 | } 178 | } 179 | 180 | #endif /* point_field_conversion.h */ 181 | -------------------------------------------------------------------------------- /sensor_msgs/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | \b sensor_msgs is a package which collects the common message data types for 6 | robot sensors. It also provides a set of methods for conversion between these 7 | data types. 8 | 9 | 10 | */ 11 | -------------------------------------------------------------------------------- /sensor_msgs/msg/BatteryState.msg: -------------------------------------------------------------------------------- 1 | 2 | # Constants are chosen to match the enums in the linux kernel 3 | # defined in include/linux/power_supply.h as of version 3.7 4 | # The one difference is for style reasons the constants are 5 | # all uppercase not mixed case. 6 | 7 | # Power supply status constants 8 | uint8 POWER_SUPPLY_STATUS_UNKNOWN = 0 9 | uint8 POWER_SUPPLY_STATUS_CHARGING = 1 10 | uint8 POWER_SUPPLY_STATUS_DISCHARGING = 2 11 | uint8 POWER_SUPPLY_STATUS_NOT_CHARGING = 3 12 | uint8 POWER_SUPPLY_STATUS_FULL = 4 13 | 14 | # Power supply health constants 15 | uint8 POWER_SUPPLY_HEALTH_UNKNOWN = 0 16 | uint8 POWER_SUPPLY_HEALTH_GOOD = 1 17 | uint8 POWER_SUPPLY_HEALTH_OVERHEAT = 2 18 | uint8 POWER_SUPPLY_HEALTH_DEAD = 3 19 | uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4 20 | uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5 21 | uint8 POWER_SUPPLY_HEALTH_COLD = 6 22 | uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7 23 | uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8 24 | 25 | # Power supply technology (chemistry) constants 26 | uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0 27 | uint8 POWER_SUPPLY_TECHNOLOGY_NIMH = 1 28 | uint8 POWER_SUPPLY_TECHNOLOGY_LION = 2 29 | uint8 POWER_SUPPLY_TECHNOLOGY_LIPO = 3 30 | uint8 POWER_SUPPLY_TECHNOLOGY_LIFE = 4 31 | uint8 POWER_SUPPLY_TECHNOLOGY_NICD = 5 32 | uint8 POWER_SUPPLY_TECHNOLOGY_LIMN = 6 33 | 34 | Header header 35 | float32 voltage # Voltage in Volts (Mandatory) 36 | float32 temperature # Temperature in Degrees Celsius (If unmeasured NaN) 37 | float32 current # Negative when discharging (A) (If unmeasured NaN) 38 | float32 charge # Current charge in Ah (If unmeasured NaN) 39 | float32 capacity # Capacity in Ah (last full capacity) (If unmeasured NaN) 40 | float32 design_capacity # Capacity in Ah (design capacity) (If unmeasured NaN) 41 | float32 percentage # Charge percentage on 0 to 1 range (If unmeasured NaN) 42 | uint8 power_supply_status # The charging status as reported. Values defined above 43 | uint8 power_supply_health # The battery health metric. Values defined above 44 | uint8 power_supply_technology # The battery chemistry. Values defined above 45 | bool present # True if the battery is present 46 | 47 | float32[] cell_voltage # An array of individual cell voltages for each cell in the pack 48 | # If individual voltages unknown but number of cells known set each to NaN 49 | float32[] cell_temperature # An array of individual cell temperatures for each cell in the pack 50 | # If individual temperatures unknown but number of cells known set each to NaN 51 | string location # The location into which the battery is inserted. (slot number or plug) 52 | string serial_number # The best approximation of the battery serial number 53 | -------------------------------------------------------------------------------- /sensor_msgs/msg/CameraInfo.msg: -------------------------------------------------------------------------------- 1 | # This message defines meta information for a camera. It should be in a 2 | # camera namespace on topic "camera_info" and accompanied by up to five 3 | # image topics named: 4 | # 5 | # image_raw - raw data from the camera driver, possibly Bayer encoded 6 | # image - monochrome, distorted 7 | # image_color - color, distorted 8 | # image_rect - monochrome, rectified 9 | # image_rect_color - color, rectified 10 | # 11 | # The image_pipeline contains packages (image_proc, stereo_image_proc) 12 | # for producing the four processed image topics from image_raw and 13 | # camera_info. The meaning of the camera parameters are described in 14 | # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. 15 | # 16 | # The image_geometry package provides a user-friendly interface to 17 | # common operations using this meta information. If you want to, e.g., 18 | # project a 3d point into image coordinates, we strongly recommend 19 | # using image_geometry. 20 | # 21 | # If the camera is uncalibrated, the matrices D, K, R, P should be left 22 | # zeroed out. In particular, clients may assume that K[0] == 0.0 23 | # indicates an uncalibrated camera. 24 | 25 | ####################################################################### 26 | # Image acquisition info # 27 | ####################################################################### 28 | 29 | # Time of image acquisition, camera coordinate frame ID 30 | Header header # Header timestamp should be acquisition time of image 31 | # Header frame_id should be optical frame of camera 32 | # origin of frame should be optical center of camera 33 | # +x should point to the right in the image 34 | # +y should point down in the image 35 | # +z should point into the plane of the image 36 | 37 | 38 | ####################################################################### 39 | # Calibration Parameters # 40 | ####################################################################### 41 | # These are fixed during camera calibration. Their values will be the # 42 | # same in all messages until the camera is recalibrated. Note that # 43 | # self-calibrating systems may "recalibrate" frequently. # 44 | # # 45 | # The internal parameters can be used to warp a raw (distorted) image # 46 | # to: # 47 | # 1. An undistorted image (requires D and K) # 48 | # 2. A rectified image (requires D, K, R) # 49 | # The projection matrix P projects 3D points into the rectified image.# 50 | ####################################################################### 51 | 52 | # The image dimensions with which the camera was calibrated. Normally 53 | # this will be the full camera resolution in pixels. 54 | uint32 height 55 | uint32 width 56 | 57 | # The distortion model used. Supported models are listed in 58 | # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a 59 | # simple model of radial and tangential distortion - is sufficient. 60 | string distortion_model 61 | 62 | # The distortion parameters, size depending on the distortion model. 63 | # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). 64 | float64[] D 65 | 66 | # Intrinsic camera matrix for the raw (distorted) images. 67 | # [fx 0 cx] 68 | # K = [ 0 fy cy] 69 | # [ 0 0 1] 70 | # Projects 3D points in the camera coordinate frame to 2D pixel 71 | # coordinates using the focal lengths (fx, fy) and principal point 72 | # (cx, cy). 73 | float64[9] K # 3x3 row-major matrix 74 | 75 | # Rectification matrix (stereo cameras only) 76 | # A rotation matrix aligning the camera coordinate system to the ideal 77 | # stereo image plane so that epipolar lines in both stereo images are 78 | # parallel. 79 | float64[9] R # 3x3 row-major matrix 80 | 81 | # Projection/camera matrix 82 | # [fx' 0 cx' Tx] 83 | # P = [ 0 fy' cy' Ty] 84 | # [ 0 0 1 0] 85 | # By convention, this matrix specifies the intrinsic (camera) matrix 86 | # of the processed (rectified) image. That is, the left 3x3 portion 87 | # is the normal camera intrinsic matrix for the rectified image. 88 | # It projects 3D points in the camera coordinate frame to 2D pixel 89 | # coordinates using the focal lengths (fx', fy') and principal point 90 | # (cx', cy') - these may differ from the values in K. 91 | # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will 92 | # also have R = the identity and P[1:3,1:3] = K. 93 | # For a stereo pair, the fourth column [Tx Ty 0]' is related to the 94 | # position of the optical center of the second camera in the first 95 | # camera's frame. We assume Tz = 0 so both cameras are in the same 96 | # stereo image plane. The first camera always has Tx = Ty = 0. For 97 | # the right (second) camera of a horizontal stereo pair, Ty = 0 and 98 | # Tx = -fx' * B, where B is the baseline between the cameras. 99 | # Given a 3D point [X Y Z]', the projection (x, y) of the point onto 100 | # the rectified image is given by: 101 | # [u v w]' = P * [X Y Z 1]' 102 | # x = u / w 103 | # y = v / w 104 | # This holds for both images of a stereo pair. 105 | float64[12] P # 3x4 row-major matrix 106 | 107 | 108 | ####################################################################### 109 | # Operational Parameters # 110 | ####################################################################### 111 | # These define the image region actually captured by the camera # 112 | # driver. Although they affect the geometry of the output image, they # 113 | # may be changed freely without recalibrating the camera. # 114 | ####################################################################### 115 | 116 | # Binning refers here to any camera setting which combines rectangular 117 | # neighborhoods of pixels into larger "super-pixels." It reduces the 118 | # resolution of the output image to 119 | # (width / binning_x) x (height / binning_y). 120 | # The default values binning_x = binning_y = 0 is considered the same 121 | # as binning_x = binning_y = 1 (no subsampling). 122 | uint32 binning_x 123 | uint32 binning_y 124 | 125 | # Region of interest (subwindow of full camera resolution), given in 126 | # full resolution (unbinned) image coordinates. A particular ROI 127 | # always denotes the same window of pixels on the camera sensor, 128 | # regardless of binning settings. 129 | # The default setting of roi (all values 0) is considered the same as 130 | # full resolution (roi.width = width, roi.height = height). 131 | RegionOfInterest roi 132 | -------------------------------------------------------------------------------- /sensor_msgs/msg/ChannelFloat32.msg: -------------------------------------------------------------------------------- 1 | # This message is used by the PointCloud message to hold optional data 2 | # associated with each point in the cloud. The length of the values 3 | # array should be the same as the length of the points array in the 4 | # PointCloud, and each value should be associated with the corresponding 5 | # point. 6 | 7 | # Channel names in existing practice include: 8 | # "u", "v" - row and column (respectively) in the left stereo image. 9 | # This is opposite to usual conventions but remains for 10 | # historical reasons. The newer PointCloud2 message has no 11 | # such problem. 12 | # "rgb" - For point clouds produced by color stereo cameras. uint8 13 | # (R,G,B) values packed into the least significant 24 bits, 14 | # in order. 15 | # "intensity" - laser or pixel intensity. 16 | # "distance" 17 | 18 | # The channel name should give semantics of the channel (e.g. 19 | # "intensity" instead of "value"). 20 | string name 21 | 22 | # The values array should be 1-1 with the elements of the associated 23 | # PointCloud. 24 | float32[] values 25 | -------------------------------------------------------------------------------- /sensor_msgs/msg/CompressedImage.msg: -------------------------------------------------------------------------------- 1 | # This message contains a compressed image 2 | 3 | Header header # Header timestamp should be acquisition time of image 4 | # Header frame_id should be optical frame of camera 5 | # origin of frame should be optical center of camera 6 | # +x should point to the right in the image 7 | # +y should point down in the image 8 | # +z should point into to plane of the image 9 | 10 | string format # Specifies the format of the data 11 | # Acceptable values differ by the image transport used: 12 | # - compressed_image_transport: 13 | # ORIG_PIXFMT; CODEC compressed [COMPRESSED_PIXFMT] 14 | # where: 15 | # - ORIG_PIXFMT is pixel format of the raw image, i.e. 16 | # the content of sensor_msgs/Image/encoding with 17 | # values from include/sensor_msgs/image_encodings.h 18 | # - CODEC is one of [jpeg, png] 19 | # - COMPRESSED_PIXFMT is only appended for color images 20 | # and is the pixel format used by the compression 21 | # algorithm. Valid values for jpeg encoding are: 22 | # [bgr8, rgb8]. Valid values for png encoding are: 23 | # [bgr8, rgb8, bgr16, rgb16]. 24 | # If the field is empty or does not correspond to the 25 | # above pattern, the image is treated as bgr8 or mono8 26 | # jpeg image (depending on the number of channels). 27 | # - compressed_depth_image_transport: 28 | # ORIG_PIXFMT; compressedDepth CODEC 29 | # where: 30 | # - ORIG_PIXFMT is pixel format of the raw image, i.e. 31 | # the content of sensor_msgs/Image/encoding with 32 | # values from include/sensor_msgs/image_encodings.h 33 | # It is usually one of [16UC1, 32FC1]. 34 | # - CODEC is one of [png, rvl] 35 | # If the field is empty or does not correspond to the 36 | # above pattern, the image is treated as png image. 37 | # - Other image transports can store whatever values they 38 | # need for successful decoding of the image. Refer to 39 | # documentation of the other transports for details. 40 | 41 | uint8[] data # Compressed image buffer 42 | -------------------------------------------------------------------------------- /sensor_msgs/msg/FluidPressure.msg: -------------------------------------------------------------------------------- 1 | # Single pressure reading. This message is appropriate for measuring the 2 | # pressure inside of a fluid (air, water, etc). This also includes 3 | # atmospheric or barometric pressure. 4 | 5 | # This message is not appropriate for force/pressure contact sensors. 6 | 7 | Header header # timestamp of the measurement 8 | # frame_id is the location of the pressure sensor 9 | 10 | float64 fluid_pressure # Absolute pressure reading in Pascals. 11 | 12 | float64 variance # 0 is interpreted as variance unknown -------------------------------------------------------------------------------- /sensor_msgs/msg/Illuminance.msg: -------------------------------------------------------------------------------- 1 | # Single photometric illuminance measurement. Light should be assumed to be 2 | # measured along the sensor's x-axis (the area of detection is the y-z plane). 3 | # The illuminance should have a 0 or positive value and be received with 4 | # the sensor's +X axis pointing toward the light source. 5 | 6 | # Photometric illuminance is the measure of the human eye's sensitivity of the 7 | # intensity of light encountering or passing through a surface. 8 | 9 | # All other Photometric and Radiometric measurements should 10 | # not use this message. 11 | # This message cannot represent: 12 | # Luminous intensity (candela/light source output) 13 | # Luminance (nits/light output per area) 14 | # Irradiance (watt/area), etc. 15 | 16 | Header header # timestamp is the time the illuminance was measured 17 | # frame_id is the location and direction of the reading 18 | 19 | float64 illuminance # Measurement of the Photometric Illuminance in Lux. 20 | 21 | float64 variance # 0 is interpreted as variance unknown -------------------------------------------------------------------------------- /sensor_msgs/msg/Image.msg: -------------------------------------------------------------------------------- 1 | # This message contains an uncompressed image 2 | # (0, 0) is at top-left corner of image 3 | # 4 | 5 | Header header # Header timestamp should be acquisition time of image 6 | # Header frame_id should be optical frame of camera 7 | # origin of frame should be optical center of camera 8 | # +x should point to the right in the image 9 | # +y should point down in the image 10 | # +z should point into to plane of the image 11 | # If the frame_id here and the frame_id of the CameraInfo 12 | # message associated with the image conflict 13 | # the behavior is undefined 14 | 15 | uint32 height # image height, that is, number of rows 16 | uint32 width # image width, that is, number of columns 17 | 18 | # The legal values for encoding are in file src/image_encodings.cpp 19 | # If you want to standardize a new string format, join 20 | # ros-users@lists.sourceforge.net and send an email proposing a new encoding. 21 | 22 | string encoding # Encoding of pixels -- channel meaning, ordering, size 23 | # taken from the list of strings in include/sensor_msgs/image_encodings.h 24 | 25 | uint8 is_bigendian # is this data bigendian? 26 | uint32 step # Full row length in bytes 27 | uint8[] data # actual matrix data, size is (step * rows) 28 | -------------------------------------------------------------------------------- /sensor_msgs/msg/Imu.msg: -------------------------------------------------------------------------------- 1 | # This is a message to hold data from an IMU (Inertial Measurement Unit) 2 | # 3 | # Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec 4 | # 5 | # If the covariance of the measurement is known, it should be filled in (if all you know is the 6 | # variance of each measurement, e.g. from the datasheet, just put those along the diagonal) 7 | # A covariance matrix of all zeros will be interpreted as "covariance unknown", and to use the 8 | # data a covariance will have to be assumed or gotten from some other source 9 | # 10 | # If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation 11 | # estimate), please set element 0 of the associated covariance matrix to -1 12 | # If you are interpreting this message, please check for a value of -1 in the first element of each 13 | # covariance matrix, and disregard the associated estimate. 14 | 15 | Header header 16 | 17 | geometry_msgs/Quaternion orientation 18 | float64[9] orientation_covariance # Row major about x, y, z axes 19 | 20 | geometry_msgs/Vector3 angular_velocity 21 | float64[9] angular_velocity_covariance # Row major about x, y, z axes 22 | 23 | geometry_msgs/Vector3 linear_acceleration 24 | float64[9] linear_acceleration_covariance # Row major x, y z 25 | -------------------------------------------------------------------------------- /sensor_msgs/msg/JointState.msg: -------------------------------------------------------------------------------- 1 | # This is a message that holds data to describe the state of a set of torque controlled joints. 2 | # 3 | # The state of each joint (revolute or prismatic) is defined by: 4 | # * the position of the joint (rad or m), 5 | # * the velocity of the joint (rad/s or m/s) and 6 | # * the effort that is applied in the joint (Nm or N). 7 | # 8 | # Each joint is uniquely identified by its name 9 | # The header specifies the time at which the joint states were recorded. All the joint states 10 | # in one message have to be recorded at the same time. 11 | # 12 | # This message consists of a multiple arrays, one for each part of the joint state. 13 | # The goal is to make each of the fields optional. When e.g. your joints have no 14 | # effort associated with them, you can leave the effort array empty. 15 | # 16 | # All arrays in this message should have the same size, or be empty. 17 | # This is the only way to uniquely associate the joint name with the correct 18 | # states. 19 | 20 | 21 | Header header 22 | 23 | string[] name 24 | float64[] position 25 | float64[] velocity 26 | float64[] effort 27 | -------------------------------------------------------------------------------- /sensor_msgs/msg/Joy.msg: -------------------------------------------------------------------------------- 1 | # Reports the state of a joysticks axes and buttons. 2 | Header header # timestamp in the header is the time the data is received from the joystick 3 | float32[] axes # the axes measurements from a joystick 4 | int32[] buttons # the buttons measurements from a joystick 5 | -------------------------------------------------------------------------------- /sensor_msgs/msg/JoyFeedback.msg: -------------------------------------------------------------------------------- 1 | # Declare of the type of feedback 2 | uint8 TYPE_LED = 0 3 | uint8 TYPE_RUMBLE = 1 4 | uint8 TYPE_BUZZER = 2 5 | 6 | uint8 type 7 | 8 | # This will hold an id number for each type of each feedback. 9 | # Example, the first led would be id=0, the second would be id=1 10 | uint8 id 11 | 12 | # Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is 13 | # actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on. 14 | float32 intensity 15 | 16 | -------------------------------------------------------------------------------- /sensor_msgs/msg/JoyFeedbackArray.msg: -------------------------------------------------------------------------------- 1 | # This message publishes values for multiple feedback at once. 2 | JoyFeedback[] array -------------------------------------------------------------------------------- /sensor_msgs/msg/LaserEcho.msg: -------------------------------------------------------------------------------- 1 | # This message is a submessage of MultiEchoLaserScan and is not intended 2 | # to be used separately. 3 | 4 | float32[] echoes # Multiple values of ranges or intensities. 5 | # Each array represents data from the same angle increment. -------------------------------------------------------------------------------- /sensor_msgs/msg/LaserScan.msg: -------------------------------------------------------------------------------- 1 | # Single scan from a planar laser range-finder 2 | # 3 | # If you have another ranging device with different behavior (e.g. a sonar 4 | # array), please find or create a different message, since applications 5 | # will make fairly laser-specific assumptions about this data 6 | 7 | Header header # timestamp in the header is the acquisition time of 8 | # the first ray in the scan. 9 | # 10 | # in frame frame_id, angles are measured around 11 | # the positive Z axis (counterclockwise, if Z is up) 12 | # with zero angle being forward along the x axis 13 | 14 | float32 angle_min # start angle of the scan [rad] 15 | float32 angle_max # end angle of the scan [rad] 16 | float32 angle_increment # angular distance between measurements [rad] 17 | 18 | float32 time_increment # time between measurements [seconds] - if your scanner 19 | # is moving, this will be used in interpolating position 20 | # of 3d points 21 | float32 scan_time # time between scans [seconds] 22 | 23 | float32 range_min # minimum range value [m] 24 | float32 range_max # maximum range value [m] 25 | 26 | float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded) 27 | float32[] intensities # intensity data [device-specific units]. If your 28 | # device does not provide intensities, please leave 29 | # the array empty. 30 | -------------------------------------------------------------------------------- /sensor_msgs/msg/MagneticField.msg: -------------------------------------------------------------------------------- 1 | # Measurement of the Magnetic Field vector at a specific location. 2 | 3 | # If the covariance of the measurement is known, it should be filled in 4 | # (if all you know is the variance of each measurement, e.g. from the datasheet, 5 | #just put those along the diagonal) 6 | # A covariance matrix of all zeros will be interpreted as "covariance unknown", 7 | # and to use the data a covariance will have to be assumed or gotten from some 8 | # other source 9 | 10 | 11 | Header header # timestamp is the time the 12 | # field was measured 13 | # frame_id is the location and orientation 14 | # of the field measurement 15 | 16 | geometry_msgs/Vector3 magnetic_field # x, y, and z components of the 17 | # field vector in Tesla 18 | # If your sensor does not output 3 axes, 19 | # put NaNs in the components not reported. 20 | 21 | float64[9] magnetic_field_covariance # Row major about x, y, z axes 22 | # 0 is interpreted as variance unknown -------------------------------------------------------------------------------- /sensor_msgs/msg/MultiDOFJointState.msg: -------------------------------------------------------------------------------- 1 | # Representation of state for joints with multiple degrees of freedom, 2 | # following the structure of JointState. 3 | # 4 | # It is assumed that a joint in a system corresponds to a transform that gets applied 5 | # along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw) 6 | # and those 3DOF can be expressed as a transformation matrix, and that transformation 7 | # matrix can be converted back to (x, y, yaw) 8 | # 9 | # Each joint is uniquely identified by its name 10 | # The header specifies the time at which the joint states were recorded. All the joint states 11 | # in one message have to be recorded at the same time. 12 | # 13 | # This message consists of a multiple arrays, one for each part of the joint state. 14 | # The goal is to make each of the fields optional. When e.g. your joints have no 15 | # wrench associated with them, you can leave the wrench array empty. 16 | # 17 | # All arrays in this message should have the same size, or be empty. 18 | # This is the only way to uniquely associate the joint name with the correct 19 | # states. 20 | 21 | Header header 22 | 23 | string[] joint_names 24 | geometry_msgs/Transform[] transforms 25 | geometry_msgs/Twist[] twist 26 | geometry_msgs/Wrench[] wrench 27 | -------------------------------------------------------------------------------- /sensor_msgs/msg/MultiEchoLaserScan.msg: -------------------------------------------------------------------------------- 1 | # Single scan from a multi-echo planar laser range-finder 2 | # 3 | # If you have another ranging device with different behavior (e.g. a sonar 4 | # array), please find or create a different message, since applications 5 | # will make fairly laser-specific assumptions about this data 6 | 7 | Header header # timestamp in the header is the acquisition time of 8 | # the first ray in the scan. 9 | # 10 | # in frame frame_id, angles are measured around 11 | # the positive Z axis (counterclockwise, if Z is up) 12 | # with zero angle being forward along the x axis 13 | 14 | float32 angle_min # start angle of the scan [rad] 15 | float32 angle_max # end angle of the scan [rad] 16 | float32 angle_increment # angular distance between measurements [rad] 17 | 18 | float32 time_increment # time between measurements [seconds] - if your scanner 19 | # is moving, this will be used in interpolating position 20 | # of 3d points 21 | float32 scan_time # time between scans [seconds] 22 | 23 | float32 range_min # minimum range value [m] 24 | float32 range_max # maximum range value [m] 25 | 26 | LaserEcho[] ranges # range data [m] (Note: NaNs, values < range_min or > range_max should be discarded) 27 | # +Inf measurements are out of range 28 | # -Inf measurements are too close to determine exact distance. 29 | LaserEcho[] intensities # intensity data [device-specific units]. If your 30 | # device does not provide intensities, please leave 31 | # the array empty. -------------------------------------------------------------------------------- /sensor_msgs/msg/NavSatFix.msg: -------------------------------------------------------------------------------- 1 | # Navigation Satellite fix for any Global Navigation Satellite System 2 | # 3 | # Specified using the WGS 84 reference ellipsoid 4 | 5 | # header.stamp specifies the ROS time for this measurement (the 6 | # corresponding satellite time may be reported using the 7 | # sensor_msgs/TimeReference message). 8 | # 9 | # header.frame_id is the frame of reference reported by the satellite 10 | # receiver, usually the location of the antenna. This is a 11 | # Euclidean frame relative to the vehicle, not a reference 12 | # ellipsoid. 13 | Header header 14 | 15 | # satellite fix status information 16 | NavSatStatus status 17 | 18 | # Latitude [degrees]. Positive is north of equator; negative is south. 19 | float64 latitude 20 | 21 | # Longitude [degrees]. Positive is east of prime meridian; negative is west. 22 | float64 longitude 23 | 24 | # Altitude [m]. Positive is above the WGS 84 ellipsoid 25 | # (quiet NaN if no altitude is available). 26 | float64 altitude 27 | 28 | # Position covariance [m^2] defined relative to a tangential plane 29 | # through the reported position. The components are East, North, and 30 | # Up (ENU), in row-major order. 31 | # 32 | # Beware: this coordinate system exhibits singularities at the poles. 33 | 34 | float64[9] position_covariance 35 | 36 | # If the covariance of the fix is known, fill it in completely. If the 37 | # GPS receiver provides the variance of each measurement, put them 38 | # along the diagonal. If only Dilution of Precision is available, 39 | # estimate an approximate covariance from that. 40 | 41 | uint8 COVARIANCE_TYPE_UNKNOWN = 0 42 | uint8 COVARIANCE_TYPE_APPROXIMATED = 1 43 | uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 44 | uint8 COVARIANCE_TYPE_KNOWN = 3 45 | 46 | uint8 position_covariance_type 47 | -------------------------------------------------------------------------------- /sensor_msgs/msg/NavSatStatus.msg: -------------------------------------------------------------------------------- 1 | # Navigation Satellite fix status for any Global Navigation Satellite System 2 | 3 | # Whether to output an augmented fix is determined by both the fix 4 | # type and the last time differential corrections were received. A 5 | # fix is valid when status >= STATUS_FIX. 6 | 7 | int8 STATUS_NO_FIX = -1 # unable to fix position 8 | int8 STATUS_FIX = 0 # unaugmented fix 9 | int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation 10 | int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation 11 | 12 | int8 status 13 | 14 | # Bits defining which Global Navigation Satellite System signals were 15 | # used by the receiver. 16 | 17 | uint16 SERVICE_GPS = 1 18 | uint16 SERVICE_GLONASS = 2 19 | uint16 SERVICE_COMPASS = 4 # includes BeiDou. 20 | uint16 SERVICE_GALILEO = 8 21 | 22 | uint16 service 23 | -------------------------------------------------------------------------------- /sensor_msgs/msg/PointCloud.msg: -------------------------------------------------------------------------------- 1 | # This message holds a collection of 3d points, plus optional additional 2 | # information about each point. 3 | 4 | # Time of sensor data acquisition, coordinate frame ID. 5 | Header header 6 | 7 | # Array of 3d points. Each Point32 should be interpreted as a 3d point 8 | # in the frame given in the header. 9 | geometry_msgs/Point32[] points 10 | 11 | # Each channel should have the same number of elements as points array, 12 | # and the data in each channel should correspond 1:1 with each point. 13 | # Channel names in common practice are listed in ChannelFloat32.msg. 14 | ChannelFloat32[] channels 15 | -------------------------------------------------------------------------------- /sensor_msgs/msg/PointCloud2.msg: -------------------------------------------------------------------------------- 1 | # This message holds a collection of N-dimensional points, which may 2 | # contain additional information such as normals, intensity, etc. The 3 | # point data is stored as a binary blob, its layout described by the 4 | # contents of the "fields" array. 5 | 6 | # The point cloud data may be organized 2d (image-like) or 1d 7 | # (unordered). Point clouds organized as 2d images may be produced by 8 | # camera depth sensors such as stereo or time-of-flight. 9 | 10 | # Time of sensor data acquisition, and the coordinate frame ID (for 3d 11 | # points). 12 | Header header 13 | 14 | # 2D structure of the point cloud. If the cloud is unordered, height is 15 | # 1 and width is the length of the point cloud. 16 | uint32 height 17 | uint32 width 18 | 19 | # Describes the channels and their layout in the binary data blob. 20 | PointField[] fields 21 | 22 | bool is_bigendian # Is this data bigendian? 23 | uint32 point_step # Length of a point in bytes 24 | uint32 row_step # Length of a row in bytes 25 | uint8[] data # Actual point data, size is (row_step*height) 26 | 27 | bool is_dense # True if there are no invalid points 28 | -------------------------------------------------------------------------------- /sensor_msgs/msg/PointField.msg: -------------------------------------------------------------------------------- 1 | # This message holds the description of one point entry in the 2 | # PointCloud2 message format. 3 | uint8 INT8 = 1 4 | uint8 UINT8 = 2 5 | uint8 INT16 = 3 6 | uint8 UINT16 = 4 7 | uint8 INT32 = 5 8 | uint8 UINT32 = 6 9 | uint8 FLOAT32 = 7 10 | uint8 FLOAT64 = 8 11 | 12 | string name # Name of field 13 | uint32 offset # Offset from start of point struct 14 | uint8 datatype # Datatype enumeration, see above 15 | uint32 count # How many elements in the field 16 | -------------------------------------------------------------------------------- /sensor_msgs/msg/Range.msg: -------------------------------------------------------------------------------- 1 | # Single range reading from an active ranger that emits energy and reports 2 | # one range reading that is valid along an arc at the distance measured. 3 | # This message is not appropriate for laser scanners. See the LaserScan 4 | # message if you are working with a laser scanner. 5 | 6 | # This message also can represent a fixed-distance (binary) ranger. This 7 | # sensor will have min_range===max_range===distance of detection. 8 | # These sensors follow REP 117 and will output -Inf if the object is detected 9 | # and +Inf if the object is outside of the detection range. 10 | 11 | Header header # timestamp in the header is the time the ranger 12 | # returned the distance reading 13 | 14 | # Radiation type enums 15 | # If you want a value added to this list, send an email to the ros-users list 16 | uint8 ULTRASOUND=0 17 | uint8 INFRARED=1 18 | 19 | uint8 radiation_type # the type of radiation used by the sensor 20 | # (sound, IR, etc) [enum] 21 | 22 | float32 field_of_view # the size of the arc that the distance reading is 23 | # valid for [rad] 24 | # the object causing the range reading may have 25 | # been anywhere within -field_of_view/2 and 26 | # field_of_view/2 at the measured range. 27 | # 0 angle corresponds to the x-axis of the sensor. 28 | 29 | float32 min_range # minimum range value [m] 30 | float32 max_range # maximum range value [m] 31 | # Fixed distance rangers require min_range==max_range 32 | 33 | float32 range # range data [m] 34 | # (Note: values < range_min or > range_max 35 | # should be discarded) 36 | # Fixed distance rangers only output -Inf or +Inf. 37 | # -Inf represents a detection within fixed distance. 38 | # (Detection too close to the sensor to quantify) 39 | # +Inf represents no detection within the fixed distance. 40 | # (Object out of range) -------------------------------------------------------------------------------- /sensor_msgs/msg/RegionOfInterest.msg: -------------------------------------------------------------------------------- 1 | # This message is used to specify a region of interest within an image. 2 | # 3 | # When used to specify the ROI setting of the camera when the image was 4 | # taken, the height and width fields should either match the height and 5 | # width fields for the associated image; or height = width = 0 6 | # indicates that the full resolution image was captured. 7 | 8 | uint32 x_offset # Leftmost pixel of the ROI 9 | # (0 if the ROI includes the left edge of the image) 10 | uint32 y_offset # Topmost pixel of the ROI 11 | # (0 if the ROI includes the top edge of the image) 12 | uint32 height # Height of ROI 13 | uint32 width # Width of ROI 14 | 15 | # True if a distinct rectified ROI should be calculated from the "raw" 16 | # ROI in this message. Typically this should be False if the full image 17 | # is captured (ROI not used), and True if a subwindow is captured (ROI 18 | # used). 19 | bool do_rectify 20 | -------------------------------------------------------------------------------- /sensor_msgs/msg/RelativeHumidity.msg: -------------------------------------------------------------------------------- 1 | # Single reading from a relative humidity sensor. Defines the ratio of partial 2 | # pressure of water vapor to the saturated vapor pressure at a temperature. 3 | 4 | Header header # timestamp of the measurement 5 | # frame_id is the location of the humidity sensor 6 | 7 | float64 relative_humidity # Expression of the relative humidity 8 | # from 0.0 to 1.0. 9 | # 0.0 is no partial pressure of water vapor 10 | # 1.0 represents partial pressure of saturation 11 | 12 | float64 variance # 0 is interpreted as variance unknown -------------------------------------------------------------------------------- /sensor_msgs/msg/Temperature.msg: -------------------------------------------------------------------------------- 1 | # Single temperature reading. 2 | 3 | Header header # timestamp is the time the temperature was measured 4 | # frame_id is the location of the temperature reading 5 | 6 | float64 temperature # Measurement of the Temperature in Degrees Celsius 7 | 8 | float64 variance # 0 is interpreted as variance unknown 9 | -------------------------------------------------------------------------------- /sensor_msgs/msg/TimeReference.msg: -------------------------------------------------------------------------------- 1 | # Measurement from an external time source not actively synchronized with the system clock. 2 | 3 | Header header # stamp is system time for which measurement was valid 4 | # frame_id is not used 5 | 6 | time time_ref # corresponding time from this external source 7 | string source # (optional) name of time source 8 | -------------------------------------------------------------------------------- /sensor_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 5 | 6 | sensor_msgs 7 | 1.13.2 8 | 9 | This package defines messages for commonly used sensors, including 10 | cameras and scanning laser rangefinders. 11 | 12 | Michel Hidalgo 13 | BSD 14 | 15 | http://ros.org/wiki/sensor_msgs 16 | Tully Foote 17 | 18 | catkin 19 | python-setuptools 20 | python3-setuptools 21 | 22 | geometry_msgs 23 | message_generation 24 | std_msgs 25 | 26 | geometry_msgs 27 | message_runtime 28 | std_msgs 29 | 30 | rosbag 31 | rosunit 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | -------------------------------------------------------------------------------- /sensor_msgs/setup.py: -------------------------------------------------------------------------------- 1 | from setuptools import setup 2 | from catkin_pkg.python_setup import generate_distutils_setup 3 | 4 | d = generate_distutils_setup( 5 | ## don't do this unless you want a globally visible script 6 | # scripts=['bin/myscript'], 7 | packages=['sensor_msgs'], 8 | package_dir={'': 'src'} 9 | ) 10 | 11 | setup(**d) 12 | -------------------------------------------------------------------------------- /sensor_msgs/src/sensor_msgs/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ros/common_msgs/092bc230c8153dd4cfee0c84c9796cc7e6b09fdb/sensor_msgs/src/sensor_msgs/__init__.py -------------------------------------------------------------------------------- /sensor_msgs/src/sensor_msgs/point_cloud2.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | 3 | # Software License Agreement (BSD License) 4 | # 5 | # Copyright (c) 2008, Willow Garage, Inc. 6 | # All rights reserved. 7 | # 8 | # Redistribution and use in source and binary forms, with or without 9 | # modification, are permitted provided that the following conditions 10 | # are met: 11 | # 12 | # * Redistributions of source code must retain the above copyright 13 | # notice, this list of conditions and the following disclaimer. 14 | # * Redistributions in binary form must reproduce the above 15 | # copyright notice, this list of conditions and the following 16 | # disclaimer in the documentation and/or other materials provided 17 | # with the distribution. 18 | # * Neither the name of Willow Garage, Inc. nor the names of its 19 | # contributors may be used to endorse or promote products derived 20 | # from this software without specific prior written permission. 21 | # 22 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 23 | # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 24 | # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 25 | # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 26 | # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 27 | # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 28 | # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 29 | # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 30 | # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 31 | # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 32 | # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 33 | # POSSIBILITY OF SUCH DAMAGE. 34 | 35 | from __future__ import print_function 36 | 37 | """ 38 | Serialization of sensor_msgs.PointCloud2 messages. 39 | 40 | Author: Tim Field 41 | """ 42 | 43 | from collections import namedtuple 44 | import ctypes 45 | import math 46 | import struct 47 | 48 | import roslib.message 49 | from sensor_msgs.msg import PointCloud2, PointField 50 | 51 | _DATATYPES = {} 52 | _DATATYPES[PointField.INT8] = ('b', 1) 53 | _DATATYPES[PointField.UINT8] = ('B', 1) 54 | _DATATYPES[PointField.INT16] = ('h', 2) 55 | _DATATYPES[PointField.UINT16] = ('H', 2) 56 | _DATATYPES[PointField.INT32] = ('i', 4) 57 | _DATATYPES[PointField.UINT32] = ('I', 4) 58 | _DATATYPES[PointField.FLOAT32] = ('f', 4) 59 | _DATATYPES[PointField.FLOAT64] = ('d', 8) 60 | 61 | def read_points(cloud, field_names=None, skip_nans=False, uvs=[]): 62 | """ 63 | Read points from a L{sensor_msgs.PointCloud2} message. 64 | 65 | @param cloud: The point cloud to read from. 66 | @type cloud: L{sensor_msgs.PointCloud2} 67 | @param field_names: The names of fields to read. If None, read all fields. [default: None] 68 | @type field_names: iterable 69 | @param skip_nans: If True, then don't return any point with a NaN value. 70 | @type skip_nans: bool [default: False] 71 | @param uvs: If specified, then only return the points at the given coordinates. [default: empty list] 72 | @type uvs: iterable 73 | @return: Generator which yields a list of values for each point. 74 | @rtype: generator 75 | """ 76 | assert isinstance(cloud, roslib.message.Message) and cloud._type == 'sensor_msgs/PointCloud2', 'cloud is not a sensor_msgs.msg.PointCloud2' 77 | fmt = _get_struct_fmt(cloud.is_bigendian, cloud.fields, field_names) 78 | width, height, point_step, row_step, data, isnan = cloud.width, cloud.height, cloud.point_step, cloud.row_step, cloud.data, math.isnan 79 | unpack_from = struct.Struct(fmt).unpack_from 80 | 81 | if skip_nans: 82 | if uvs: 83 | for u, v in uvs: 84 | p = unpack_from(data, (row_step * v) + (point_step * u)) 85 | has_nan = False 86 | for pv in p: 87 | if isnan(pv): 88 | has_nan = True 89 | break 90 | if not has_nan: 91 | yield p 92 | else: 93 | for v in range(height): 94 | offset = row_step * v 95 | for u in range(width): 96 | p = unpack_from(data, offset) 97 | has_nan = False 98 | for pv in p: 99 | if isnan(pv): 100 | has_nan = True 101 | break 102 | if not has_nan: 103 | yield p 104 | offset += point_step 105 | else: 106 | if uvs: 107 | for u, v in uvs: 108 | yield unpack_from(data, (row_step * v) + (point_step * u)) 109 | else: 110 | for v in range(height): 111 | offset = row_step * v 112 | for u in range(width): 113 | yield unpack_from(data, offset) 114 | offset += point_step 115 | 116 | def read_points_list(cloud, field_names=None, skip_nans=False, uvs=[]): 117 | """ 118 | Read points from a L{sensor_msgs.PointCloud2} message. This function returns a list of namedtuples. 119 | It operates on top of the read_points method. For more efficient access use read_points directly. 120 | 121 | @param cloud: The point cloud to read from. 122 | @type cloud: L{sensor_msgs.PointCloud2} 123 | @param field_names: The names of fields to read. If None, read all fields. [default: None] 124 | @type field_names: iterable 125 | @param skip_nans: If True, then don't return any point with a NaN value. 126 | @type skip_nans: bool [default: False] 127 | @param uvs: If specified, then only return the points at the given coordinates. [default: empty list] 128 | @type uvs: iterable 129 | @return: List of namedtuples containing the values for each point 130 | @rtype: list 131 | """ 132 | assert isinstance(cloud, roslib.message.Message) and cloud._type == 'sensor_msgs/PointCloud2', 'cloud is not a sensor_msgs.msg.PointCloud2' 133 | 134 | if field_names is None: 135 | field_names = [f.name for f in cloud.fields] 136 | 137 | Point = namedtuple("Point", field_names) 138 | 139 | return [Point._make(l) for l in read_points(cloud, field_names, skip_nans, uvs)] 140 | 141 | def create_cloud(header, fields, points): 142 | """ 143 | Create a L{sensor_msgs.msg.PointCloud2} message. 144 | 145 | @param header: The point cloud header. 146 | @type header: L{std_msgs.msg.Header} 147 | @param fields: The point cloud fields. 148 | @type fields: iterable of L{sensor_msgs.msg.PointField} 149 | @param points: The point cloud points. 150 | @type points: list of iterables, i.e. one iterable for each point, with the 151 | elements of each iterable being the values of the fields for 152 | that point (in the same order as the fields parameter) 153 | @return: The point cloud. 154 | @rtype: L{sensor_msgs.msg.PointCloud2} 155 | """ 156 | 157 | cloud_struct = struct.Struct(_get_struct_fmt(False, fields)) 158 | 159 | buff = ctypes.create_string_buffer(cloud_struct.size * len(points)) 160 | 161 | point_step, pack_into = cloud_struct.size, cloud_struct.pack_into 162 | offset = 0 163 | for p in points: 164 | pack_into(buff, offset, *p) 165 | offset += point_step 166 | 167 | return PointCloud2(header=header, 168 | height=1, 169 | width=len(points), 170 | is_dense=False, 171 | is_bigendian=False, 172 | fields=fields, 173 | point_step=cloud_struct.size, 174 | row_step=cloud_struct.size * len(points), 175 | data=buff.raw) 176 | 177 | def create_cloud_xyz32(header, points): 178 | """ 179 | Create a L{sensor_msgs.msg.PointCloud2} message with 3 float32 fields (x, y, z). 180 | 181 | @param header: The point cloud header. 182 | @type header: L{std_msgs.msg.Header} 183 | @param points: The point cloud points. 184 | @type points: iterable 185 | @return: The point cloud. 186 | @rtype: L{sensor_msgs.msg.PointCloud2} 187 | """ 188 | fields = [PointField('x', 0, PointField.FLOAT32, 1), 189 | PointField('y', 4, PointField.FLOAT32, 1), 190 | PointField('z', 8, PointField.FLOAT32, 1)] 191 | return create_cloud(header, fields, points) 192 | 193 | def _get_struct_fmt(is_bigendian, fields, field_names=None): 194 | fmt = '>' if is_bigendian else '<' 195 | 196 | offset = 0 197 | for field in (f for f in sorted(fields, key=lambda f: f.offset) if field_names is None or f.name in field_names): 198 | if offset < field.offset: 199 | fmt += 'x' * (field.offset - offset) 200 | offset = field.offset 201 | if field.datatype not in _DATATYPES: 202 | print('Skipping unknown PointField datatype [%d]' % field.datatype, file=sys.stderr) 203 | else: 204 | datatype_fmt, datatype_length = _DATATYPES[field.datatype] 205 | fmt += field.count * datatype_fmt 206 | offset += field.count * datatype_length 207 | 208 | return fmt 209 | -------------------------------------------------------------------------------- /sensor_msgs/srv/SetCameraInfo.srv: -------------------------------------------------------------------------------- 1 | # This service requests that a camera stores the given CameraInfo 2 | # as that camera's calibration information. 3 | # 4 | # The width and height in the camera_info field should match what the 5 | # camera is currently outputting on its camera_info topic, and the camera 6 | # will assume that the region of the imager that is being referred to is 7 | # the region that the camera is currently capturing. 8 | 9 | sensor_msgs/CameraInfo camera_info # The camera_info to store 10 | --- 11 | bool success # True if the call succeeded 12 | string status_message # Used to give details about success 13 | -------------------------------------------------------------------------------- /sensor_msgs/test/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | include_directories(${catkin_INCLUDE_DIRS}) 2 | catkin_add_gtest(${PROJECT_NAME}_test main.cpp) 3 | catkin_add_gtest(${PROJECT_NAME}_test_image_encodings test_image_encodings.cpp) 4 | if(TARGET sensor_msgs_test) 5 | add_dependencies(${PROJECT_NAME}_test ${sensor_msgs_EXPORTED_TARGETS}) 6 | endif() 7 | 8 | -------------------------------------------------------------------------------- /sensor_msgs/test/main.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2013, Open Source Robotics Foundation 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of Willow Garage, Inc. nor the names of its 18 | * contributors may be used to endorse or promote products derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | */ 34 | 35 | #include 36 | 37 | #define _GLIBCXX_DEBUG // Enable assertions in STL 38 | 39 | #include 40 | 41 | TEST(sensor_msgs, PointCloud2Iterator_Empty) 42 | { 43 | EXPECT_EXIT({ 44 | sensor_msgs::PointCloud2 cloud_msg; 45 | cloud_msg.width = 1; 46 | sensor_msgs::PointCloud2Modifier modifier(cloud_msg); 47 | modifier.setPointCloud2FieldsByString(1, "xyz"); 48 | 49 | sensor_msgs::PointCloud2Iterator iter_x(cloud_msg, "x"); 50 | 51 | exit(0); 52 | }, ::testing::ExitedWithCode(0), ""); 53 | } 54 | 55 | TEST(sensor_msgs, PointCloud2Iterator) 56 | { 57 | // Create a dummy PointCloud2 58 | int n_points = 4; 59 | sensor_msgs::PointCloud2 cloud_msg_1, cloud_msg_2; 60 | cloud_msg_1.height = n_points; 61 | cloud_msg_1.width = 1; 62 | sensor_msgs::PointCloud2Modifier modifier(cloud_msg_1); 63 | modifier.setPointCloud2FieldsByString(2, "xyz", "rgb"); 64 | cloud_msg_2 = cloud_msg_1; 65 | 66 | // Fill 1 by hand 67 | float point_data_raw[] = {1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0, 11.0, 12.0}; 68 | std::vector point_data(point_data_raw, point_data_raw + 3*n_points); 69 | // colors in RGB order 70 | uint8_t color_data_raw[] = {40, 80, 120, 160, 200, 240, 20, 40, 60, 80, 100, 120}; 71 | std::vector color_data(color_data_raw, color_data_raw + 3*n_points); 72 | 73 | float *data = reinterpret_cast(&cloud_msg_1.data.front()); 74 | for(size_t n=0, i=0; n(data++); 80 | // add the colors in order BGRA like PCL 81 | size_t j_max = 2; 82 | for(size_t j = 0; j <= j_max; ++j) 83 | *(bgr++) = color_data[3*n+(j_max - j)]; 84 | // Add 3 extra floats of padding 85 | data += 3; 86 | } 87 | 88 | // Fill 2 using an iterator 89 | sensor_msgs::PointCloud2Iterator iter_x(cloud_msg_2, "x"); 90 | sensor_msgs::PointCloud2Iterator iter_r(cloud_msg_2, "r"); 91 | sensor_msgs::PointCloud2Iterator iter_g(cloud_msg_2, "g"); 92 | sensor_msgs::PointCloud2Iterator iter_b(cloud_msg_2, "b"); 93 | for(size_t i=0; i iter_const_1_x(cloud_msg_1, "x"), iter_const_2_x(cloud_msg_2, "x"); 104 | sensor_msgs::PointCloud2ConstIterator iter_const_1_y(cloud_msg_1, "y"), iter_const_2_y(cloud_msg_2, "y"); 105 | sensor_msgs::PointCloud2ConstIterator iter_const_1_z(cloud_msg_1, "z"), iter_const_2_z(cloud_msg_2, "z"); 106 | sensor_msgs::PointCloud2ConstIterator iter_const_1_r(cloud_msg_1, "r"), iter_const_2_r(cloud_msg_2, "r"); 107 | sensor_msgs::PointCloud2ConstIterator iter_const_1_g(cloud_msg_1, "g"), iter_const_2_g(cloud_msg_2, "g"); 108 | sensor_msgs::PointCloud2ConstIterator iter_const_1_b(cloud_msg_1, "b"), iter_const_2_b(cloud_msg_2, "b"); 109 | 110 | size_t i=0; 111 | for(; iter_const_1_x != iter_const_1_x.end(); ++i, ++iter_const_1_x, ++iter_const_2_x, ++iter_const_1_y, ++iter_const_2_y, 112 | ++iter_const_1_z, ++iter_const_2_z, ++iter_const_1_r, ++iter_const_1_g, ++iter_const_1_b) { 113 | EXPECT_EQ(*iter_const_1_x, *iter_const_2_x); 114 | EXPECT_EQ(*iter_const_1_x, point_data[0+3*i]); 115 | EXPECT_EQ(*iter_const_1_y, *iter_const_2_y); 116 | EXPECT_EQ(*iter_const_1_y, point_data[1+3*i]); 117 | EXPECT_EQ(*iter_const_1_z, *iter_const_2_z); 118 | EXPECT_EQ(*iter_const_1_z, point_data[2+3*i]); 119 | EXPECT_EQ(*iter_const_1_r, *iter_const_2_r); 120 | EXPECT_EQ(*iter_const_1_r, color_data[3*i+0]); 121 | EXPECT_EQ(*iter_const_1_g, *iter_const_2_g); 122 | EXPECT_EQ(*iter_const_1_g, color_data[3*i+1]); 123 | EXPECT_EQ(*iter_const_1_b, *iter_const_2_b); 124 | EXPECT_EQ(*iter_const_1_b, color_data[3*i+2]); 125 | // This is to test the different operators 126 | ++iter_const_2_r; 127 | iter_const_2_g += 1; 128 | iter_const_2_b = iter_const_2_b + 1; 129 | } 130 | EXPECT_FALSE(iter_const_1_y != iter_const_1_y.end()); 131 | EXPECT_FALSE(iter_const_1_z != iter_const_1_z.end()); 132 | EXPECT_FALSE(iter_const_1_r != iter_const_1_r.end()); 133 | EXPECT_FALSE(iter_const_1_g != iter_const_1_g.end()); 134 | EXPECT_FALSE(iter_const_1_b != iter_const_1_b.end()); 135 | EXPECT_FALSE(iter_const_2_x != iter_const_2_x.end()); 136 | EXPECT_FALSE(iter_const_2_y != iter_const_2_y.end()); 137 | EXPECT_FALSE(iter_const_2_z != iter_const_2_z.end()); 138 | EXPECT_FALSE(iter_const_2_r != iter_const_2_r.end()); 139 | EXPECT_FALSE(iter_const_2_g != iter_const_2_g.end()); 140 | EXPECT_FALSE(iter_const_2_b != iter_const_2_b.end()); 141 | EXPECT_EQ(i, n_points); 142 | } 143 | 144 | int main(int argc, char** argv) 145 | { 146 | ::testing::InitGoogleTest(&argc, argv); 147 | return RUN_ALL_TESTS(); 148 | } 149 | -------------------------------------------------------------------------------- /sensor_msgs/test/test_image_encodings.cpp: -------------------------------------------------------------------------------- 1 | /* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2016, Kentaro Wada. 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of Willow Garage, Inc. nor the names of its 18 | * contributors may be used to endorse or promote products derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | */ 34 | 35 | #include 36 | 37 | #include 38 | 39 | TEST(sensor_msgs, NumChannels) 40 | { 41 | ASSERT_EQ(sensor_msgs::image_encodings::numChannels("mono8"), 1); 42 | ASSERT_EQ(sensor_msgs::image_encodings::numChannels("rgb8"), 3); 43 | ASSERT_EQ(sensor_msgs::image_encodings::numChannels("8UC"), 1); 44 | ASSERT_EQ(sensor_msgs::image_encodings::numChannels("8UC3"), 3); 45 | ASSERT_EQ(sensor_msgs::image_encodings::numChannels("8UC10"), 10); 46 | ASSERT_EQ(sensor_msgs::image_encodings::numChannels("16UC"), 1); 47 | ASSERT_EQ(sensor_msgs::image_encodings::numChannels("16UC3"), 3); 48 | ASSERT_EQ(sensor_msgs::image_encodings::numChannels("16UC10"), 10); 49 | ASSERT_EQ(sensor_msgs::image_encodings::numChannels("32SC"), 1); 50 | ASSERT_EQ(sensor_msgs::image_encodings::numChannels("32SC3"), 3); 51 | ASSERT_EQ(sensor_msgs::image_encodings::numChannels("32SC10"), 10); 52 | ASSERT_EQ(sensor_msgs::image_encodings::numChannels("64FC"), 1); 53 | ASSERT_EQ(sensor_msgs::image_encodings::numChannels("64FC3"), 3); 54 | ASSERT_EQ(sensor_msgs::image_encodings::numChannels("64FC10"), 10); 55 | } 56 | 57 | TEST(sensor_msgs, bitDepth) 58 | { 59 | ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("mono8"), 8); 60 | ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("rgb8"), 8); 61 | ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("8UC"), 8); 62 | ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("8UC3"), 8); 63 | ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("8UC10"), 8); 64 | ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("16UC"), 16); 65 | ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("16UC3"), 16); 66 | ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("16UC10"), 16); 67 | ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("32SC"), 32); 68 | ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("32SC3"), 32); 69 | ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("32SC10"), 32); 70 | ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("64FC"), 64); 71 | ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("64FC3"), 64); 72 | ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("64FC10"), 64); 73 | } 74 | 75 | int main(int argc, char** argv) 76 | { 77 | ::testing::InitGoogleTest(&argc, argv); 78 | return RUN_ALL_TESTS(); 79 | } 80 | -------------------------------------------------------------------------------- /shape_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package shape_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.13.2 (2025-04-25) 6 | ------------------- 7 | 8 | 1.13.1 (2021-01-11) 9 | ------------------- 10 | * Update package maintainers (`#168 `_) 11 | * Contributors: Michel Hidalgo 12 | 13 | 1.13.0 (2020-05-21) 14 | ------------------- 15 | * Bump CMake version to avoid CMP0048 warning (`#158 `_) 16 | * Contributors: Shane Loretz 17 | 18 | 1.12.7 (2018-11-06) 19 | ------------------- 20 | 21 | 1.12.6 (2018-05-03) 22 | ------------------- 23 | 24 | 1.12.5 (2016-09-30) 25 | ------------------- 26 | 27 | 1.12.4 (2016-02-22) 28 | ------------------- 29 | 30 | 1.12.3 (2015-04-20) 31 | ------------------- 32 | 33 | 1.12.2 (2015-03-21) 34 | ------------------- 35 | 36 | 1.12.1 (2015-03-17) 37 | ------------------- 38 | * updating outdated urls. fixes `#52 `_. 39 | * Contributors: Tully Foote 40 | 41 | 1.12.0 (2014-12-29) 42 | ------------------- 43 | 44 | 1.11.6 (2014-11-04) 45 | ------------------- 46 | 47 | 1.11.5 (2014-10-27) 48 | ------------------- 49 | 50 | 1.11.4 (2014-06-19) 51 | ------------------- 52 | 53 | 1.11.3 (2014-05-07) 54 | ------------------- 55 | * Export architecture_independent flag in package.xml 56 | * Contributors: Scott K Logan 57 | 58 | 1.11.2 (2014-04-24) 59 | ------------------- 60 | 61 | 1.11.1 (2014-04-16) 62 | ------------------- 63 | 64 | 1.11.0 (2014-03-04) 65 | ------------------- 66 | 67 | 1.10.6 (2014-02-27) 68 | ------------------- 69 | 70 | 1.10.5 (2014-02-25) 71 | ------------------- 72 | 73 | 1.10.4 (2014-02-18) 74 | ------------------- 75 | * Add a description to shape_msgs. 76 | * Contributors: Michael Ferguson 77 | 78 | 1.10.3 (2014-01-07) 79 | ------------------- 80 | 81 | 1.10.2 (2013-08-19) 82 | ------------------- 83 | 84 | 1.10.1 (2013-08-16) 85 | ------------------- 86 | 87 | 1.10.0 (2013-07-13) 88 | ------------------- 89 | 90 | 1.9.16 (2013-05-21) 91 | ------------------- 92 | 93 | 1.9.15 (2013-03-08) 94 | ------------------- 95 | 96 | 1.9.14 (2013-01-19) 97 | ------------------- 98 | 99 | 1.9.13 (2013-01-13) 100 | ------------------- 101 | 102 | 1.9.12 (2013-01-02) 103 | ------------------- 104 | 105 | 1.9.11 (2012-12-17) 106 | ------------------- 107 | * modified dep type of catkin 108 | 109 | 1.9.10 (2012-12-13) 110 | ------------------- 111 | * add missing downstream depend 112 | * switched from langs to message_* packages 113 | 114 | 1.9.9 (2012-11-22) 115 | ------------------ 116 | 117 | 1.9.8 (2012-11-14) 118 | ------------------ 119 | 120 | 1.9.7 (2012-10-30) 121 | ------------------ 122 | * fix catkin function order 123 | 124 | 1.9.6 (2012-10-18) 125 | ------------------ 126 | * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 127 | 128 | 1.9.5 (2012-09-28) 129 | ------------------ 130 | * fixed missing find genmsg 131 | 132 | 1.9.4 (2012-09-27 18:06) 133 | ------------------------ 134 | 135 | 1.9.3 (2012-09-27 17:39) 136 | ------------------------ 137 | * cleanup 138 | * updated to latest catkin 139 | * fixed dependencies and more 140 | * updated to latest catkin: created package.xmls, updated CmakeLists.txt 141 | 142 | 1.9.2 (2012-09-05) 143 | ------------------ 144 | * updated pkg-config in manifest.xml 145 | 146 | 1.9.1 (2012-09-04) 147 | ------------------ 148 | * use install destination variables, removed manual installation of manifests 149 | 150 | 1.9.0 (2012-08-29) 151 | ------------------ 152 | * updated to current catkin 153 | 154 | 1.8.13 (2012-07-26 18:34:15 +0000) 155 | ---------------------------------- 156 | * Add more comments, change the types to uint8 157 | * updates to shape based on discussion with vincent (and dave h.) 158 | * removing un-needed stack.sml 159 | * updated deps 160 | * one more convention 161 | * more changes after talking to Dave 162 | * update per Tully's latest comments 163 | * more work on shapes, based on reviews 164 | * apply updates from Tully 165 | * removing C++ code from shapes_msgs 166 | * shange comment as Dave suggested 167 | 168 | 1.8.8 (2012-06-12 22:36) 169 | ------------------------ 170 | * update ID values so they resemble markers better 171 | * address Vincent's comments 172 | * applying Sachin's comments 173 | * add shape msgs 174 | -------------------------------------------------------------------------------- /shape_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(shape_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation std_msgs) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | Mesh.msg 10 | MeshTriangle.msg 11 | Plane.msg 12 | SolidPrimitive.msg) 13 | 14 | generate_messages(DEPENDENCIES geometry_msgs std_msgs) 15 | 16 | catkin_package(CATKIN_DEPENDS geometry_msgs message_runtime std_msgs) 17 | -------------------------------------------------------------------------------- /shape_msgs/msg/Mesh.msg: -------------------------------------------------------------------------------- 1 | # Definition of a mesh 2 | 3 | # list of triangles; the index values refer to positions in vertices[] 4 | MeshTriangle[] triangles 5 | 6 | # the actual vertices that make up the mesh 7 | geometry_msgs/Point[] vertices 8 | -------------------------------------------------------------------------------- /shape_msgs/msg/MeshTriangle.msg: -------------------------------------------------------------------------------- 1 | # Definition of a triangle's vertices 2 | uint32[3] vertex_indices 3 | -------------------------------------------------------------------------------- /shape_msgs/msg/Plane.msg: -------------------------------------------------------------------------------- 1 | # Representation of a plane, using the plane equation ax + by + cz + d = 0 2 | 3 | # a := coef[0] 4 | # b := coef[1] 5 | # c := coef[2] 6 | # d := coef[3] 7 | 8 | float64[4] coef 9 | -------------------------------------------------------------------------------- /shape_msgs/msg/SolidPrimitive.msg: -------------------------------------------------------------------------------- 1 | # Define box, sphere, cylinder, cone 2 | # All shapes are defined to have their bounding boxes centered around 0,0,0. 3 | 4 | uint8 BOX=1 5 | uint8 SPHERE=2 6 | uint8 CYLINDER=3 7 | uint8 CONE=4 8 | 9 | # The type of the shape 10 | uint8 type 11 | 12 | 13 | # The dimensions of the shape 14 | float64[] dimensions 15 | 16 | # The meaning of the shape dimensions: each constant defines the index in the 'dimensions' array 17 | 18 | # For the BOX type, the X, Y, and Z dimensions are the length of the corresponding 19 | # sides of the box. 20 | uint8 BOX_X=0 21 | uint8 BOX_Y=1 22 | uint8 BOX_Z=2 23 | 24 | 25 | # For the SPHERE type, only one component is used, and it gives the radius of 26 | # the sphere. 27 | uint8 SPHERE_RADIUS=0 28 | 29 | 30 | # For the CYLINDER and CONE types, the center line is oriented along 31 | # the Z axis. Therefore the CYLINDER_HEIGHT (CONE_HEIGHT) component 32 | # of dimensions gives the height of the cylinder (cone). The 33 | # CYLINDER_RADIUS (CONE_RADIUS) component of dimensions gives the 34 | # radius of the base of the cylinder (cone). Cone and cylinder 35 | # primitives are defined to be circular. The tip of the cone is 36 | # pointing up, along +Z axis. 37 | 38 | uint8 CYLINDER_HEIGHT=0 39 | uint8 CYLINDER_RADIUS=1 40 | 41 | uint8 CONE_HEIGHT=0 42 | uint8 CONE_RADIUS=1 43 | -------------------------------------------------------------------------------- /shape_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | shape_msgs 3 | 1.13.2 4 | 5 | This package contains messages for defining shapes, such as simple solid 6 | object primitives (cube, sphere, etc), planes, and meshes. 7 | 8 | Michel Hidalgo 9 | BSD 10 | 11 | http://wiki.ros.org/shape_msgs 12 | Ioan Sucan 13 | 14 | catkin 15 | 16 | geometry_msgs 17 | message_generation 18 | std_msgs 19 | 20 | geometry_msgs 21 | message_runtime 22 | std_msgs 23 | 24 | 25 | 26 | 27 | 28 | -------------------------------------------------------------------------------- /stereo_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package stereo_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.13.2 (2025-04-25) 6 | ------------------- 7 | 8 | 1.13.1 (2021-01-11) 9 | ------------------- 10 | * Update package maintainers (`#168 `_) 11 | * Contributors: Michel Hidalgo 12 | 13 | 1.13.0 (2020-05-21) 14 | ------------------- 15 | * Bump CMake version to avoid CMP0048 warning (`#158 `_) 16 | * Contributors: Shane Loretz 17 | 18 | 1.12.7 (2018-11-06) 19 | ------------------- 20 | 21 | 1.12.6 (2018-05-03) 22 | ------------------- 23 | 24 | 1.12.5 (2016-09-30) 25 | ------------------- 26 | * Fix spelling mistakes 27 | * Contributors: trorornmn 28 | 29 | 1.12.4 (2016-02-22) 30 | ------------------- 31 | 32 | 1.12.3 (2015-04-20) 33 | ------------------- 34 | 35 | 1.12.2 (2015-03-21) 36 | ------------------- 37 | 38 | 1.12.1 (2015-03-17) 39 | ------------------- 40 | * updating outdated urls. fixes `#52 `_. 41 | * Contributors: Tully Foote 42 | 43 | 1.12.0 (2014-12-29) 44 | ------------------- 45 | 46 | 1.11.6 (2014-11-04) 47 | ------------------- 48 | 49 | 1.11.5 (2014-10-27) 50 | ------------------- 51 | 52 | 1.11.4 (2014-06-19) 53 | ------------------- 54 | 55 | 1.11.3 (2014-05-07) 56 | ------------------- 57 | * Export architecture_independent flag in package.xml 58 | * Contributors: Scott K Logan 59 | 60 | 1.11.2 (2014-04-24) 61 | ------------------- 62 | 63 | 1.11.1 (2014-04-16) 64 | ------------------- 65 | 66 | 1.11.0 (2014-03-04) 67 | ------------------- 68 | 69 | 1.10.6 (2014-02-27) 70 | ------------------- 71 | 72 | 1.10.5 (2014-02-25) 73 | ------------------- 74 | 75 | 1.10.4 (2014-02-18) 76 | ------------------- 77 | 78 | 1.10.3 (2014-01-07) 79 | ------------------- 80 | 81 | 1.10.2 (2013-08-19) 82 | ------------------- 83 | 84 | 1.10.1 (2013-08-16) 85 | ------------------- 86 | 87 | 1.10.0 (2013-07-13) 88 | ------------------- 89 | 90 | 1.9.16 (2013-05-21) 91 | ------------------- 92 | * update email in package.xml 93 | 94 | 1.9.15 (2013-03-08) 95 | ------------------- 96 | 97 | 1.9.14 (2013-01-19) 98 | ------------------- 99 | 100 | 1.9.13 (2013-01-13) 101 | ------------------- 102 | 103 | 1.9.12 (2013-01-02) 104 | ------------------- 105 | 106 | 1.9.11 (2012-12-17) 107 | ------------------- 108 | * modified dep type of catkin 109 | 110 | 1.9.10 (2012-12-13) 111 | ------------------- 112 | * add missing downstream depend 113 | * switched from langs to message_* packages 114 | 115 | 1.9.9 (2012-11-22) 116 | ------------------ 117 | 118 | 1.9.8 (2012-11-14) 119 | ------------------ 120 | 121 | 1.9.7 (2012-10-30) 122 | ------------------ 123 | * fix catkin function order 124 | 125 | 1.9.6 (2012-10-18) 126 | ------------------ 127 | * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 128 | 129 | 1.9.5 (2012-09-28) 130 | ------------------ 131 | * fixed missing find genmsg 132 | 133 | 1.9.4 (2012-09-27 18:06) 134 | ------------------------ 135 | 136 | 1.9.3 (2012-09-27 17:39) 137 | ------------------------ 138 | * cleanup 139 | * updated to latest catkin 140 | * fixed dependencies and more 141 | * updated to latest catkin: created package.xmls, updated CmakeLists.txt 142 | 143 | 1.9.2 (2012-09-05) 144 | ------------------ 145 | * updated pkg-config in manifest.xml 146 | 147 | 1.9.1 (2012-09-04) 148 | ------------------ 149 | * use install destination variables, removed manual installation of manifests 150 | 151 | 1.9.0 (2012-08-29) 152 | ------------------ 153 | 154 | 1.8.13 (2012-07-26 18:34:15 +0000) 155 | ---------------------------------- 156 | 157 | 1.8.8 (2012-06-12 22:36) 158 | ------------------------ 159 | * removed obsolete catkin tag from manifest files 160 | * fixed package dependencies for several common messages (fixed `#3956 `_) 161 | * adding manifest exports 162 | * removed depend, added catkin 163 | * stripping depend and export tags from common_msgs manifests as msg dependencies are now declared in cmake and stack.yaml. Also removed bag migration exports 164 | * common_msgs: removing migration rules as all are over a year old 165 | * bye bye vestigial MSG_DIRS 166 | * stereo_msgs: catkin'd 167 | * adios rosbuild2 in manifest.xml 168 | * missing dependencies 169 | * updating bagmigration exports 170 | * rosbuild2 taking shape 171 | * removing old exports for msg/cpp and reving to 1.3.7 in preparation for release 172 | * stereo_msgs into common_msgs `#4637 `_ 173 | -------------------------------------------------------------------------------- /stereo_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(stereo_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS sensor_msgs message_generation std_msgs) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | DisparityImage.msg) 10 | 11 | generate_messages(DEPENDENCIES sensor_msgs std_msgs) 12 | 13 | catkin_package(CATKIN_DEPENDS message_runtime sensor_msgs std_msgs) 14 | -------------------------------------------------------------------------------- /stereo_msgs/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | \b stereo_msgs contains messages for representing stereo-related data. 6 | 7 | */ 8 | -------------------------------------------------------------------------------- /stereo_msgs/msg/DisparityImage.msg: -------------------------------------------------------------------------------- 1 | # Separate header for compatibility with current TimeSynchronizer. 2 | # Likely to be removed in a later release, use image.header instead. 3 | Header header 4 | 5 | # Floating point disparity image. The disparities are pre-adjusted for any 6 | # x-offset between the principal points of the two cameras (in the case 7 | # that they are verged). That is: d = x_l - x_r - (cx_l - cx_r) 8 | sensor_msgs/Image image 9 | 10 | # Stereo geometry. For disparity d, the depth from the camera is Z = fT/d. 11 | float32 f # Focal length, pixels 12 | float32 T # Baseline, world units 13 | 14 | # Subwindow of (potentially) valid disparity values. 15 | sensor_msgs/RegionOfInterest valid_window 16 | 17 | # The range of disparities searched. 18 | # In the disparity image, any disparity less than min_disparity is invalid. 19 | # The disparity search range defines the horopter, or 3D volume that the 20 | # stereo algorithm can "see". Points with Z outside of: 21 | # Z_min = fT / max_disparity 22 | # Z_max = fT / min_disparity 23 | # could not be found. 24 | float32 min_disparity 25 | float32 max_disparity 26 | 27 | # Smallest allowed disparity increment. The smallest achievable depth range 28 | # resolution is delta_Z = (Z^2/fT)*delta_d. 29 | float32 delta_d 30 | -------------------------------------------------------------------------------- /stereo_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | stereo_msgs 3 | 1.13.2 4 | 5 | stereo_msgs contains messages specific to stereo processing, such as disparity images. 6 | 7 | Michel Hidalgo 8 | BSD 9 | 10 | http://wiki.ros.org/stereo_msgs 11 | Patrick Mihelich 12 | Kurt Konolige 13 | Tully Foote 14 | 15 | catkin 16 | 17 | message_generation 18 | sensor_msgs 19 | std_msgs 20 | 21 | message_runtime 22 | sensor_msgs 23 | std_msgs 24 | 25 | 26 | 27 | 28 | 29 | -------------------------------------------------------------------------------- /trajectory_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package trajectory_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.13.2 (2025-04-25) 6 | ------------------- 7 | 8 | 1.13.1 (2021-01-11) 9 | ------------------- 10 | * Update package maintainers (`#168 `_) 11 | * Contributors: Michel Hidalgo 12 | 13 | 1.13.0 (2020-05-21) 14 | ------------------- 15 | * Bump CMake version to avoid CMP0048 warning (`#158 `_) 16 | * Fix EOF line break so cat output is more usable. 17 | * Contributors: Halie Murray-Davis, Shane Loretz 18 | 19 | 1.12.7 (2018-11-06) 20 | ------------------- 21 | 22 | 1.12.6 (2018-05-03) 23 | ------------------- 24 | 25 | 1.12.5 (2016-09-30) 26 | ------------------- 27 | * Fix spelling mistakes 28 | * Contributors: trorornmn 29 | 30 | 1.12.4 (2016-02-22) 31 | ------------------- 32 | 33 | 1.12.3 (2015-04-20) 34 | ------------------- 35 | 36 | 1.12.2 (2015-03-21) 37 | ------------------- 38 | 39 | 1.12.1 (2015-03-17) 40 | ------------------- 41 | * updating outdated urls. fixes `#52 `_. 42 | * Contributors: Tully Foote 43 | 44 | 1.12.0 (2014-12-29) 45 | ------------------- 46 | 47 | 1.11.6 (2014-11-04) 48 | ------------------- 49 | 50 | 1.11.5 (2014-10-27) 51 | ------------------- 52 | 53 | 1.11.4 (2014-06-19) 54 | ------------------- 55 | 56 | 1.11.3 (2014-05-07) 57 | ------------------- 58 | * Export architecture_independent flag in package.xml 59 | * Contributors: Scott K Logan 60 | 61 | 1.11.2 (2014-04-24) 62 | ------------------- 63 | 64 | 1.11.1 (2014-04-16) 65 | ------------------- 66 | 67 | 1.11.0 (2014-03-04) 68 | ------------------- 69 | 70 | 1.10.6 (2014-02-27) 71 | ------------------- 72 | 73 | 1.10.5 (2014-02-25) 74 | ------------------- 75 | 76 | 1.10.4 (2014-02-18) 77 | ------------------- 78 | * make link to control messages a real link 79 | * Add a description to trajectory_msgs 80 | * Contributors: Michael Ferguson 81 | 82 | 1.10.3 (2014-01-07) 83 | ------------------- 84 | 85 | 1.10.2 (2013-08-19) 86 | ------------------- 87 | 88 | 1.10.1 (2013-08-16) 89 | ------------------- 90 | * add effort for JointTrajectoryPoint `#13 ` 91 | * fixing maintainer 92 | * updating maintainer 93 | 94 | 1.10.0 (2013-07-13) 95 | ------------------- 96 | * add MultiDOFJointTrajectory 97 | 98 | 1.9.16 (2013-05-21) 99 | ------------------- 100 | 101 | 1.9.15 (2013-03-08) 102 | ------------------- 103 | 104 | 1.9.14 (2013-01-19) 105 | ------------------- 106 | 107 | 1.9.13 (2013-01-13) 108 | ------------------- 109 | 110 | 1.9.12 (2013-01-02) 111 | ------------------- 112 | 113 | 1.9.11 (2012-12-17) 114 | ------------------- 115 | * modified dep type of catkin 116 | 117 | 1.9.10 (2012-12-13) 118 | ------------------- 119 | * add missing downstream depend 120 | * switched from langs to message_* packages 121 | 122 | 1.9.9 (2012-11-22) 123 | ------------------ 124 | 125 | 1.9.8 (2012-11-14) 126 | ------------------ 127 | 128 | 1.9.7 (2012-10-30) 129 | ------------------ 130 | * fix catkin function order 131 | 132 | 1.9.6 (2012-10-18) 133 | ------------------ 134 | * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 135 | 136 | 1.9.5 (2012-09-28) 137 | ------------------ 138 | * fixed missing find genmsg 139 | 140 | 1.9.4 (2012-09-27 18:06) 141 | ------------------------ 142 | 143 | 1.9.3 (2012-09-27 17:39) 144 | ------------------------ 145 | * cleanup 146 | * updated to latest catkin 147 | * fixed dependencies and more 148 | * updated to latest catkin: created package.xmls, updated CmakeLists.txt 149 | 150 | 1.9.2 (2012-09-05) 151 | ------------------ 152 | * updated pkg-config in manifest.xml 153 | 154 | 1.9.1 (2012-09-04) 155 | ------------------ 156 | * use install destination variables, removed manual installation of manifests 157 | 158 | 1.9.0 (2012-08-29) 159 | ------------------ 160 | 161 | 1.8.13 (2012-07-26 18:34:15 +0000) 162 | ---------------------------------- 163 | 164 | 1.8.8 (2012-06-12 22:36) 165 | ------------------------ 166 | * removed obsolete catkin tag from manifest files 167 | * add missing packages 168 | * adding manifest exports 169 | * removed depend, added catkin 170 | * stripping depend and export tags from common_msgs manifests as msg dependencies are now declared in cmake and stack.yaml. Also removed bag migration exports 171 | * trajectory_msgs: catkin'd 172 | * common_msgs: starting catkin conversion 173 | * adios rosbuild2 in manifest.xml 174 | * rosbuild2 taking shape 175 | * removing old exports for msg/cpp and reving to 1.3.7 in preparation for release 176 | * migrating trajectory_msgs to common_msgs from pr2_controllers `#4675 `_ 177 | -------------------------------------------------------------------------------- /trajectory_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(trajectory_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS message_generation std_msgs geometry_msgs) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | JointTrajectory.msg 10 | JointTrajectoryPoint.msg 11 | MultiDOFJointTrajectory.msg 12 | MultiDOFJointTrajectoryPoint.msg 13 | ) 14 | 15 | generate_messages(DEPENDENCIES std_msgs geometry_msgs) 16 | 17 | catkin_package(CATKIN_DEPENDS message_runtime std_msgs geometry_msgs) 18 | 19 | install(DIRECTORY rules 20 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 21 | -------------------------------------------------------------------------------- /trajectory_msgs/msg/JointTrajectory.msg: -------------------------------------------------------------------------------- 1 | Header header 2 | string[] joint_names 3 | JointTrajectoryPoint[] points 4 | -------------------------------------------------------------------------------- /trajectory_msgs/msg/JointTrajectoryPoint.msg: -------------------------------------------------------------------------------- 1 | # Each trajectory point specifies either positions[, velocities[, accelerations]] 2 | # or positions[, effort] for the trajectory to be executed. 3 | # All specified values are in the same order as the joint names in JointTrajectory.msg 4 | 5 | float64[] positions 6 | float64[] velocities 7 | float64[] accelerations 8 | float64[] effort 9 | duration time_from_start 10 | -------------------------------------------------------------------------------- /trajectory_msgs/msg/MultiDOFJointTrajectory.msg: -------------------------------------------------------------------------------- 1 | # The header is used to specify the coordinate frame and the reference time for the trajectory durations 2 | Header header 3 | 4 | # A representation of a multi-dof joint trajectory (each point is a transformation) 5 | # Each point along the trajectory will include an array of positions/velocities/accelerations 6 | # that has the same length as the array of joint names, and has the same order of joints as 7 | # the joint names array. 8 | 9 | string[] joint_names 10 | MultiDOFJointTrajectoryPoint[] points 11 | -------------------------------------------------------------------------------- /trajectory_msgs/msg/MultiDOFJointTrajectoryPoint.msg: -------------------------------------------------------------------------------- 1 | # Each multi-dof joint can specify a transform (up to 6 DOF) 2 | geometry_msgs/Transform[] transforms 3 | 4 | # There can be a velocity specified for the origin of the joint 5 | geometry_msgs/Twist[] velocities 6 | 7 | # There can be an acceleration specified for the origin of the joint 8 | geometry_msgs/Twist[] accelerations 9 | 10 | duration time_from_start 11 | -------------------------------------------------------------------------------- /trajectory_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | trajectory_msgs 3 | 1.13.2 4 | 5 | This package defines messages for defining robot trajectories. These messages are 6 | also the building blocks of most of the 7 | control_msgs actions. 8 | 9 | Michel Hidalgo 10 | BSD 11 | 12 | http://wiki.ros.org/trajectory_msgs 13 | Stuart Glaser 14 | Tully Foote 15 | 16 | catkin 17 | 18 | message_generation 19 | geometry_msgs 20 | std_msgs 21 | 22 | message_runtime 23 | geometry_msgs 24 | std_msgs 25 | rosbag_migration_rule 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | -------------------------------------------------------------------------------- /trajectory_msgs/rules/JointTrajectoryPoint_Groovy2Hydro_08.10.2013.bmr: -------------------------------------------------------------------------------- 1 | class update_trajectory_msgs_JointTrajectoryPoint_84fd2dcf68773c3dc0e9db894f4e8b40(MessageUpdateRule): 2 | old_type = "trajectory_msgs/JointTrajectoryPoint" 3 | old_full_text = """ 4 | float64[] positions 5 | float64[] velocities 6 | float64[] accelerations 7 | duration time_from_start 8 | """ 9 | 10 | new_type = "trajectory_msgs/JointTrajectoryPoint" 11 | new_full_text = """ 12 | # Each trajectory point specifies either positions[, velocities[, accelerations]] 13 | # or positions[, effort] for the trajectory to be executed. 14 | # All specified values are in the same order as the joint names in JointTrajectory.msg 15 | 16 | float64[] positions 17 | float64[] velocities 18 | float64[] accelerations 19 | float64[] effort 20 | duration time_from_start 21 | """ 22 | 23 | order = 0 24 | migrated_types = [] 25 | 26 | valid = True 27 | 28 | def update(self, old_msg, new_msg): 29 | new_msg.positions = old_msg.positions 30 | new_msg.velocities = old_msg.velocities 31 | new_msg.accelerations = old_msg.accelerations 32 | #No matching field name in old message 33 | new_msg.effort = [] 34 | new_msg.time_from_start = old_msg.time_from_start 35 | -------------------------------------------------------------------------------- /visualization_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package visualization_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.13.2 (2025-04-25) 6 | ------------------- 7 | 8 | 1.13.1 (2021-01-11) 9 | ------------------- 10 | * Update package maintainers (`#168 `_) 11 | * Contributors: Michel Hidalgo 12 | 13 | 1.13.0 (2020-05-21) 14 | ------------------- 15 | * Bump CMake version to avoid CMP0048 warning (`#158 `_) 16 | * Contributors: Shane Loretz 17 | 18 | 1.12.7 (2018-11-06) 19 | ------------------- 20 | 21 | 1.12.6 (2018-05-03) 22 | ------------------- 23 | 24 | 1.12.5 (2016-09-30) 25 | ------------------- 26 | * Fix spelling mistakes 27 | * Contributors: trorornmn 28 | 29 | 1.12.4 (2016-02-22) 30 | ------------------- 31 | 32 | 1.12.3 (2015-04-20) 33 | ------------------- 34 | 35 | 1.12.2 (2015-03-21) 36 | ------------------- 37 | 38 | 1.12.1 (2015-03-17) 39 | ------------------- 40 | 41 | 1.12.0 (2014-12-29) 42 | ------------------- 43 | * Enable DELETEALL=3 definition for marker action. Fixes `#39 `_ 44 | * Contributors: Tully Foote 45 | 46 | 1.11.6 (2014-11-04) 47 | ------------------- 48 | 49 | 1.11.5 (2014-10-27) 50 | ------------------- 51 | 52 | 1.11.4 (2014-06-19) 53 | ------------------- 54 | * Added comment to document new Rviz Marker action 55 | * Contributors: Dave Coleman 56 | 57 | 1.11.3 (2014-05-07) 58 | ------------------- 59 | * Export architecture_independent flag in package.xml 60 | * Contributors: Scott K Logan 61 | 62 | 1.11.2 (2014-04-24) 63 | ------------------- 64 | 65 | 1.11.1 (2014-04-16) 66 | ------------------- 67 | 68 | 1.11.0 (2014-03-04) 69 | ------------------- 70 | 71 | 1.10.6 (2014-02-27) 72 | ------------------- 73 | 74 | 1.10.5 (2014-02-25) 75 | ------------------- 76 | 77 | 1.10.4 (2014-02-18) 78 | ------------------- 79 | 80 | 1.10.3 (2014-01-07) 81 | ------------------- 82 | 83 | 1.10.2 (2013-08-19) 84 | ------------------- 85 | 86 | 1.10.1 (2013-08-16) 87 | ------------------- 88 | 89 | 1.10.0 (2013-07-13) 90 | ------------------- 91 | 92 | 1.9.16 (2013-05-21) 93 | ------------------- 94 | * change comment to indicate 3D control modes can now be used with mouse. 95 | * update email in package.xml 96 | 97 | 1.9.15 (2013-03-08) 98 | ------------------- 99 | 100 | 1.9.14 (2013-01-19) 101 | ------------------- 102 | 103 | 1.9.13 (2013-01-13) 104 | ------------------- 105 | 106 | 1.9.12 (2013-01-02) 107 | ------------------- 108 | 109 | 1.9.11 (2012-12-17) 110 | ------------------- 111 | * modified dep type of catkin 112 | 113 | 1.9.10 (2012-12-13) 114 | ------------------- 115 | * add missing downstream depend 116 | * switched from langs to message_* packages 117 | 118 | 1.9.9 (2012-11-22) 119 | ------------------ 120 | 121 | 1.9.8 (2012-11-14) 122 | ------------------ 123 | 124 | 1.9.7 (2012-10-30) 125 | ------------------ 126 | * fix catkin function order 127 | 128 | 1.9.6 (2012-10-18) 129 | ------------------ 130 | * Adds 3D control modes to interactive marker msgs 131 | * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 132 | 133 | 1.9.5 (2012-09-28) 134 | ------------------ 135 | * fixed missing find genmsg 136 | 137 | 1.9.4 (2012-09-27 18:06) 138 | ------------------------ 139 | 140 | 1.9.3 (2012-09-27 17:39) 141 | ------------------------ 142 | * cleanup 143 | * updated to latest catkin 144 | * fixed dependencies and more 145 | * updated to latest catkin: created package.xmls, updated CmakeLists.txt 146 | 147 | 1.9.2 (2012-09-05) 148 | ------------------ 149 | * updated pkg-config in manifest.xml 150 | 151 | 1.9.1 (2012-09-04) 152 | ------------------ 153 | * use install destination variables, removed manual installation of manifests 154 | 155 | 1.9.0 (2012-08-29) 156 | ------------------ 157 | 158 | 1.8.13 (2012-07-26 18:34:15 +0000) 159 | ---------------------------------- 160 | 161 | 1.8.8 (2012-06-12 22:36) 162 | ------------------------ 163 | * removed obsolete catkin tag from manifest files 164 | * fixed package dependency for another common message (`#3956 `_), removed unnecessary package name from another message 165 | * fixed package dependencies for several common messages (fixed `#3956 `_) 166 | * adding manifest exports 167 | * removed depend, added catkin 168 | * stripping depend and export tags from common_msgs manifests as msg dependencies are now declared in cmake and stack.yaml. Also removed bag migration exports 169 | * common_msgs: removing migration rules as all are over a year old 170 | * bye bye vestigial MSG_DIRS 171 | * visualization_msgs: catkin'd 172 | * adios rosbuild2 in manifest.xml 173 | * visualization_msgs: added 3D point of mouse event to InteractiveMarkerFeedback; fixed typo in comment in InteractiveMarkerControl. 174 | * visualization_msgs: moved INIT function of InteractiveMarkerUpdate.msg into its own message: InteractiveMarkerInit.msg, in accordance with bug `#5021 `_ 175 | * visualization_msgs: updated InteractiveMarker, MenuEntry, and InteractiveMarkerFeedback messages and removed Menu message per API review decision about cleaning up menu specifications 176 | * visualization_msgs: switched byte fields to uint8 per API review 177 | * visualization_msgs: clarified comment per API review 178 | * visualization_msgs: moved header to be first field of InteractiveMarkerFeedback per API review. 179 | * visualization_msgs: comments clarified per API review. 180 | * visualization_msgs: changed KEEP_ALIVE constant values in different messages to use the same value. 181 | * - added mouse_down / mouse_up events 182 | * changed layout of Menu messages 183 | * updated documentation 184 | * - added server_id, client_id; keep-alive and init updates; removed frame_locked option (now: timestamp=0) 185 | * added header to i.m. feedback 186 | * removed reference_frame again 187 | * added reference_frame_id to i.m. 188 | * updated docum., added descripion field to interactive marker, changed tool_tip to description in i.m. control 189 | * updated feedback ducomentation 190 | * PING->KEEP_ALIVE 191 | * added PING feedback type 192 | * added independent_marker_orientation to msg/InteractiveMarkerControl.msg 193 | * updated interactive marker messages 194 | * cleaned up the mess of commit `#36835 `_ 195 | * rosbuild2 updates 196 | * renamed InteractiveMarkerArray to InteractiveMarkerUpdate 197 | * updated msg/InteractiveMarkerFeedback.msg 198 | * updated interactive marker spec 199 | * updated documentation, namiing of fields for interactive ** 200 | * removed cpp interface from visualization_msgs again. too much work, too little outcome 201 | * made a better cpp interface for interactive marker generation 202 | * added view facing markers spec 203 | * added more functions to include/visualization_msgs/interactive_marker_tools.h 204 | * added initial version of interactive marker messages 205 | * rosbuild2 taking shape 206 | * removing old exports for msg/cpp and reving to 1.3.7 in preparation for release 207 | * update rosbagmigration dependency (`#4510 `_) 208 | * add visualization_msgs to common_msgs 209 | -------------------------------------------------------------------------------- /visualization_msgs/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(visualization_msgs) 3 | 4 | find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation std_msgs) 5 | 6 | add_message_files( 7 | DIRECTORY msg 8 | FILES 9 | ImageMarker.msg 10 | InteractiveMarker.msg 11 | InteractiveMarkerControl.msg 12 | InteractiveMarkerFeedback.msg 13 | InteractiveMarkerInit.msg 14 | InteractiveMarkerPose.msg 15 | InteractiveMarkerUpdate.msg 16 | MarkerArray.msg 17 | Marker.msg 18 | MenuEntry.msg 19 | ) 20 | 21 | generate_messages(DEPENDENCIES geometry_msgs std_msgs) 22 | 23 | catkin_package(CATKIN_DEPENDS geometry_msgs message_runtime std_msgs) 24 | -------------------------------------------------------------------------------- /visualization_msgs/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | \b visualization_msgs is a package to collect all visualization-related messages into one place. 6 | 7 | The messages it currently contains are: 8 | - \ref visualization_msgs::Marker 9 | - \ref visualization_msgs::MarkerArray 10 | - \ref visualization_msgs::ImageMarker 11 | - \ref visualization_msgs::Polyline 12 | 13 | */ -------------------------------------------------------------------------------- /visualization_msgs/msg/ImageMarker.msg: -------------------------------------------------------------------------------- 1 | uint8 CIRCLE=0 2 | uint8 LINE_STRIP=1 3 | uint8 LINE_LIST=2 4 | uint8 POLYGON=3 5 | uint8 POINTS=4 6 | 7 | uint8 ADD=0 8 | uint8 REMOVE=1 9 | 10 | Header header 11 | string ns # namespace, used with id to form a unique id 12 | int32 id # unique id within the namespace 13 | int32 type # CIRCLE/LINE_STRIP/etc. 14 | int32 action # ADD/REMOVE 15 | geometry_msgs/Point position # 2D, in pixel-coords 16 | float32 scale # the diameter for a circle, etc. 17 | std_msgs/ColorRGBA outline_color 18 | uint8 filled # whether to fill in the shape with color 19 | std_msgs/ColorRGBA fill_color # color [0.0-1.0] 20 | duration lifetime # How long the object should last before being automatically deleted. 0 means forever 21 | 22 | 23 | geometry_msgs/Point[] points # used for LINE_STRIP/LINE_LIST/POINTS/etc., 2D in pixel coords 24 | std_msgs/ColorRGBA[] outline_colors # a color for each line, point, etc. -------------------------------------------------------------------------------- /visualization_msgs/msg/InteractiveMarker.msg: -------------------------------------------------------------------------------- 1 | # Time/frame info. 2 | # If header.time is set to 0, the marker will be retransformed into 3 | # its frame on each timestep. You will receive the pose feedback 4 | # in the same frame. 5 | # Otherwise, you might receive feedback in a different frame. 6 | # For rviz, this will be the current 'fixed frame' set by the user. 7 | Header header 8 | 9 | # Initial pose. Also, defines the pivot point for rotations. 10 | geometry_msgs/Pose pose 11 | 12 | # Identifying string. Must be globally unique in 13 | # the topic that this message is sent through. 14 | string name 15 | 16 | # Short description (< 40 characters). 17 | string description 18 | 19 | # Scale to be used for default controls (default=1). 20 | float32 scale 21 | 22 | # All menu and submenu entries associated with this marker. 23 | MenuEntry[] menu_entries 24 | 25 | # List of controls displayed for this marker. 26 | InteractiveMarkerControl[] controls 27 | -------------------------------------------------------------------------------- /visualization_msgs/msg/InteractiveMarkerControl.msg: -------------------------------------------------------------------------------- 1 | # Represents a control that is to be displayed together with an interactive marker 2 | 3 | # Identifying string for this control. 4 | # You need to assign a unique value to this to receive feedback from the GUI 5 | # on what actions the user performs on this control (e.g. a button click). 6 | string name 7 | 8 | 9 | # Defines the local coordinate frame (relative to the pose of the parent 10 | # interactive marker) in which is being rotated and translated. 11 | # Default: Identity 12 | geometry_msgs/Quaternion orientation 13 | 14 | 15 | # Orientation mode: controls how orientation changes. 16 | # INHERIT: Follow orientation of interactive marker 17 | # FIXED: Keep orientation fixed at initial state 18 | # VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). 19 | uint8 INHERIT = 0 20 | uint8 FIXED = 1 21 | uint8 VIEW_FACING = 2 22 | 23 | uint8 orientation_mode 24 | 25 | # Interaction mode for this control 26 | # 27 | # NONE: This control is only meant for visualization; no context menu. 28 | # MENU: Like NONE, but right-click menu is active. 29 | # BUTTON: Element can be left-clicked. 30 | # MOVE_AXIS: Translate along local x-axis. 31 | # MOVE_PLANE: Translate in local y-z plane. 32 | # ROTATE_AXIS: Rotate around local x-axis. 33 | # MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. 34 | uint8 NONE = 0 35 | uint8 MENU = 1 36 | uint8 BUTTON = 2 37 | uint8 MOVE_AXIS = 3 38 | uint8 MOVE_PLANE = 4 39 | uint8 ROTATE_AXIS = 5 40 | uint8 MOVE_ROTATE = 6 41 | # "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. 42 | # MOVE_3D: Translate freely in 3D space. 43 | # ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. 44 | # MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. 45 | uint8 MOVE_3D = 7 46 | uint8 ROTATE_3D = 8 47 | uint8 MOVE_ROTATE_3D = 9 48 | 49 | uint8 interaction_mode 50 | 51 | 52 | # If true, the contained markers will also be visible 53 | # when the gui is not in interactive mode. 54 | bool always_visible 55 | 56 | 57 | # Markers to be displayed as custom visual representation. 58 | # Leave this empty to use the default control handles. 59 | # 60 | # Note: 61 | # - The markers can be defined in an arbitrary coordinate frame, 62 | # but will be transformed into the local frame of the interactive marker. 63 | # - If the header of a marker is empty, its pose will be interpreted as 64 | # relative to the pose of the parent interactive marker. 65 | Marker[] markers 66 | 67 | 68 | # In VIEW_FACING mode, set this to true if you don't want the markers 69 | # to be aligned with the camera view point. The markers will show up 70 | # as in INHERIT mode. 71 | bool independent_marker_orientation 72 | 73 | 74 | # Short description (< 40 characters) of what this control does, 75 | # e.g. "Move the robot". 76 | # Default: A generic description based on the interaction mode 77 | string description 78 | -------------------------------------------------------------------------------- /visualization_msgs/msg/InteractiveMarkerFeedback.msg: -------------------------------------------------------------------------------- 1 | # Time/frame info. 2 | Header header 3 | 4 | # Identifying string. Must be unique in the topic namespace. 5 | string client_id 6 | 7 | # Feedback message sent back from the GUI, e.g. 8 | # when the status of an interactive marker was modified by the user. 9 | 10 | # Specifies which interactive marker and control this message refers to 11 | string marker_name 12 | string control_name 13 | 14 | # Type of the event 15 | # KEEP_ALIVE: sent while dragging to keep up control of the marker 16 | # MENU_SELECT: a menu entry has been selected 17 | # BUTTON_CLICK: a button control has been clicked 18 | # POSE_UPDATE: the pose has been changed using one of the controls 19 | uint8 KEEP_ALIVE = 0 20 | uint8 POSE_UPDATE = 1 21 | uint8 MENU_SELECT = 2 22 | uint8 BUTTON_CLICK = 3 23 | 24 | uint8 MOUSE_DOWN = 4 25 | uint8 MOUSE_UP = 5 26 | 27 | uint8 event_type 28 | 29 | # Current pose of the marker 30 | # Note: Has to be valid for all feedback types. 31 | geometry_msgs/Pose pose 32 | 33 | # Contains the ID of the selected menu entry 34 | # Only valid for MENU_SELECT events. 35 | uint32 menu_entry_id 36 | 37 | # If event_type is BUTTON_CLICK, MOUSE_DOWN, or MOUSE_UP, mouse_point 38 | # may contain the 3 dimensional position of the event on the 39 | # control. If it does, mouse_point_valid will be true. mouse_point 40 | # will be relative to the frame listed in the header. 41 | geometry_msgs/Point mouse_point 42 | bool mouse_point_valid 43 | -------------------------------------------------------------------------------- /visualization_msgs/msg/InteractiveMarkerInit.msg: -------------------------------------------------------------------------------- 1 | # Identifying string. Must be unique in the topic namespace 2 | # that this server works on. 3 | string server_id 4 | 5 | # Sequence number. 6 | # The client will use this to detect if it has missed a subsequent 7 | # update. Every update message will have the same sequence number as 8 | # an init message. Clients will likely want to unsubscribe from the 9 | # init topic after a successful initialization to avoid receiving 10 | # duplicate data. 11 | uint64 seq_num 12 | 13 | # All markers. 14 | InteractiveMarker[] markers 15 | -------------------------------------------------------------------------------- /visualization_msgs/msg/InteractiveMarkerPose.msg: -------------------------------------------------------------------------------- 1 | # Time/frame info. 2 | Header header 3 | 4 | # Initial pose. Also, defines the pivot point for rotations. 5 | geometry_msgs/Pose pose 6 | 7 | # Identifying string. Must be globally unique in 8 | # the topic that this message is sent through. 9 | string name 10 | -------------------------------------------------------------------------------- /visualization_msgs/msg/InteractiveMarkerUpdate.msg: -------------------------------------------------------------------------------- 1 | # Identifying string. Must be unique in the topic namespace 2 | # that this server works on. 3 | string server_id 4 | 5 | # Sequence number. 6 | # The client will use this to detect if it has missed an update. 7 | uint64 seq_num 8 | 9 | # Type holds the purpose of this message. It must be one of UPDATE or KEEP_ALIVE. 10 | # UPDATE: Incremental update to previous state. 11 | # The sequence number must be 1 higher than for 12 | # the previous update. 13 | # KEEP_ALIVE: Indicates the that the server is still living. 14 | # The sequence number does not increase. 15 | # No payload data should be filled out (markers, poses, or erases). 16 | uint8 KEEP_ALIVE = 0 17 | uint8 UPDATE = 1 18 | 19 | uint8 type 20 | 21 | #Note: No guarantees on the order of processing. 22 | # Contents must be kept consistent by sender. 23 | 24 | #Markers to be added or updated 25 | InteractiveMarker[] markers 26 | 27 | #Poses of markers that should be moved 28 | InteractiveMarkerPose[] poses 29 | 30 | #Names of markers to be erased 31 | string[] erases 32 | -------------------------------------------------------------------------------- /visualization_msgs/msg/Marker.msg: -------------------------------------------------------------------------------- 1 | # See http://www.ros.org/wiki/rviz/DisplayTypes/Marker and http://www.ros.org/wiki/rviz/Tutorials/Markers%3A%20Basic%20Shapes for more information on using this message with rviz 2 | 3 | uint8 ARROW=0 4 | uint8 CUBE=1 5 | uint8 SPHERE=2 6 | uint8 CYLINDER=3 7 | uint8 LINE_STRIP=4 8 | uint8 LINE_LIST=5 9 | uint8 CUBE_LIST=6 10 | uint8 SPHERE_LIST=7 11 | uint8 POINTS=8 12 | uint8 TEXT_VIEW_FACING=9 13 | uint8 MESH_RESOURCE=10 14 | uint8 TRIANGLE_LIST=11 15 | 16 | uint8 ADD=0 17 | uint8 MODIFY=0 18 | uint8 DELETE=2 19 | uint8 DELETEALL=3 20 | 21 | Header header # header for time/frame information 22 | string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object 23 | int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later 24 | int32 type # Type of object 25 | int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects 26 | geometry_msgs/Pose pose # Pose of the object 27 | geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) 28 | std_msgs/ColorRGBA color # Color [0.0-1.0] 29 | duration lifetime # How long the object should last before being automatically deleted. 0 means forever 30 | bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep 31 | 32 | #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) 33 | geometry_msgs/Point[] points 34 | #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) 35 | #number of colors must either be 0 or equal to the number of points 36 | #NOTE: alpha is not yet used 37 | std_msgs/ColorRGBA[] colors 38 | 39 | # NOTE: only used for text markers 40 | string text 41 | 42 | # NOTE: only used for MESH_RESOURCE markers 43 | string mesh_resource 44 | bool mesh_use_embedded_materials 45 | -------------------------------------------------------------------------------- /visualization_msgs/msg/MarkerArray.msg: -------------------------------------------------------------------------------- 1 | Marker[] markers 2 | -------------------------------------------------------------------------------- /visualization_msgs/msg/MenuEntry.msg: -------------------------------------------------------------------------------- 1 | # MenuEntry message. 2 | 3 | # Each InteractiveMarker message has an array of MenuEntry messages. 4 | # A collection of MenuEntries together describe a 5 | # menu/submenu/subsubmenu/etc tree, though they are stored in a flat 6 | # array. The tree structure is represented by giving each menu entry 7 | # an ID number and a "parent_id" field. Top-level entries are the 8 | # ones with parent_id = 0. Menu entries are ordered within their 9 | # level the same way they are ordered in the containing array. Parent 10 | # entries must appear before their children. 11 | 12 | # Example: 13 | # - id = 3 14 | # parent_id = 0 15 | # title = "fun" 16 | # - id = 2 17 | # parent_id = 0 18 | # title = "robot" 19 | # - id = 4 20 | # parent_id = 2 21 | # title = "pr2" 22 | # - id = 5 23 | # parent_id = 2 24 | # title = "turtle" 25 | # 26 | # Gives a menu tree like this: 27 | # - fun 28 | # - robot 29 | # - pr2 30 | # - turtle 31 | 32 | # ID is a number for each menu entry. Must be unique within the 33 | # control, and should never be 0. 34 | uint32 id 35 | 36 | # ID of the parent of this menu entry, if it is a submenu. If this 37 | # menu entry is a top-level entry, set parent_id to 0. 38 | uint32 parent_id 39 | 40 | # menu / entry title 41 | string title 42 | 43 | # Arguments to command indicated by command_type (below) 44 | string command 45 | 46 | # Command_type stores the type of response desired when this menu 47 | # entry is clicked. 48 | # FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. 49 | # ROSRUN: execute "rosrun" with arguments given in the command field (above). 50 | # ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). 51 | uint8 FEEDBACK=0 52 | uint8 ROSRUN=1 53 | uint8 ROSLAUNCH=2 54 | uint8 command_type 55 | -------------------------------------------------------------------------------- /visualization_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | visualization_msgs 3 | 1.13.2 4 | 5 | visualization_msgs is a set of messages used by higher level packages, such as rviz, that deal in visualization-specific data. 6 | 7 | The main messages in visualization_msgs is visualization_msgs/Marker. 8 | The marker message is used to send visualization "markers" such as boxes, spheres, arrows, lines, etc. to a visualization environment such as rviz. 9 | See the rviz tutorial rviz tutorials for more information. 10 | 11 | Michel Hidalgo 12 | BSD 13 | 14 | http://ros.org/wiki/visualization_msgs 15 | Josh Faust 16 | Davis Gossow 17 | Tully Foote 18 | 19 | catkin 20 | 21 | geometry_msgs 22 | message_generation 23 | std_msgs 24 | 25 | geometry_msgs 26 | message_runtime 27 | std_msgs 28 | 29 | 30 | 31 | 32 | 33 | --------------------------------------------------------------------------------