pax_global_header00006660000000000000000000000064133717656330014530gustar00rootroot0000000000000052 comment=10b801d7dc1e8af5a68e16f6d9868b613bd7cbcf ros-common-msgs-1.12.7/000077500000000000000000000000001337176563300146605ustar00rootroot00000000000000ros-common-msgs-1.12.7/actionlib_msgs/000077500000000000000000000000001337176563300176555ustar00rootroot00000000000000ros-common-msgs-1.12.7/actionlib_msgs/CHANGELOG.rst000066400000000000000000000127061337176563300217040ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package actionlib_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.12.7 (2018-11-06) ------------------- 1.12.6 (2018-05-03) ------------------- 1.12.5 (2016-09-30) ------------------- * Fix spelling mistakes * Contributors: trorornmn 1.12.4 (2016-02-22) ------------------- 1.12.3 (2015-04-20) ------------------- 1.12.2 (2015-03-21) ------------------- 1.12.1 (2015-03-17) ------------------- * updating outdated urls. fixes `#52 `_. * Contributors: Tully Foote 1.12.0 (2014-12-29) ------------------- 1.11.6 (2014-11-04) ------------------- 1.11.5 (2014-10-27) ------------------- 1.11.4 (2014-06-19) ------------------- 1.11.3 (2014-05-07) ------------------- * Export architecture_independent flag in package.xml * Contributors: Scott K Logan 1.11.2 (2014-04-24) ------------------- 1.11.1 (2014-04-16) ------------------- 1.11.0 (2014-03-04) ------------------- 1.10.6 (2014-02-27) ------------------- * fix actionlib_msgs for dry * use catkin_install_python() to install Python scripts `#29 `_ * Contributors: Dirk Thomas 1.10.5 (2014-02-25) ------------------- * removing usage of catkin function not guaranteed available fixes `#30 `_ * Contributors: Tully Foote 1.10.4 (2014-02-18) ------------------- * remove catkin usage from CMake extra file (fix `#27 `_) * Contributors: Dirk Thomas 1.10.3 (2014-01-07) ------------------- * python 3 compatibility * prefix invocation of python script with PYTHON_EXECUTABLE (`ros/genpy#23 `_) * make generated cmake relocatable 1.10.2 (2013-08-19) ------------------- 1.10.1 (2013-08-16) ------------------- 1.10.0 (2013-07-13) ------------------- 1.9.16 (2013-05-21) ------------------- * update email in package.xml 1.9.15 (2013-03-08) ------------------- * fix handling spaces in folder names (`ros/catkin#375 `_) 1.9.14 (2013-01-19) ------------------- * fix bug using ARGV in list(FIND) directly (`ros/genmsg#18 `_) 1.9.13 (2013-01-13) ------------------- 1.9.12 (2013-01-02) ------------------- 1.9.11 (2012-12-17) ------------------- * add message_generation as a run dep for downstream * modified dep type of catkin 1.9.10 (2012-12-13) ------------------- * add missing downstream depend * switched from langs to message_* packages 1.9.9 (2012-11-22) ------------------ 1.9.8 (2012-11-14) ------------------ * add globbing for action files * updated variable to latest catkin * refactored extra file from 'in' to 'em' 1.9.7 (2012-10-30) ------------------ * fix catkin function order 1.9.6 (2012-10-18) ------------------ * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 1.9.5 (2012-09-28) ------------------ 1.9.4 (2012-09-27 18:06) ------------------------ 1.9.3 (2012-09-27 17:39) ------------------------ * cleanup * updated to latest catkin * fixed dependencies and more * updated to latest catkin: created package.xmls, updated CmakeLists.txt 1.9.2 (2012-09-05) ------------------ * updated pkg-config in manifest.xml * updated catkin variables 1.9.1 (2012-09-04) ------------------ * use install destination variables, removed manual installation of manifests 1.9.0 (2012-08-29) ------------------ * updated to current catkin 1.8.13 (2012-07-26 18:34:15 +0000) ---------------------------------- 1.8.8 (2012-06-12 22:36) ------------------------ * make find_package REQUIRED * removed obsolete catkin tag from manifest files * Fix up install-time finding of script, plus add a missing genmsg import * Convert legacy rosbuild support to use newer genaction.py script * Expose old actionlib_msgs interface to dry users. Dry actionlib builds and tests cleanly. * adding manifest exports * removed depend, added catkin * 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 * install a file that rosbuild users have hardcoded an include for * bye bye vestigial MSG_DIRS * rosbuild2 -> catkin * no include dir in actionlib_msgs * actionlib_msgs: getting rid of other build files * adios rosbuild2 in manifest.xml * catkin updates * catkin_project * catkin: only generate .msg files if .action file has changed * catkin: changed actionlib_msg to generate .msg files at cmake time * Integrate actionlib_msgs into catkin * rosbuild2 on windows tweaks (more) * rosbuild2 windows tweaks * url fix * removed extra slashes that caused trouble on OSX * rosbuild2 taking shape * rosbuild2 taking shape * removing all the extra exports * msg folder generation now parallel safe. `#4286 `_ * Fixing build dependency race condition. Trac `#4255 `_ * Added Ubuntu platform tags to manifest * Now using /usr/bin/env python. Trac `#3863 `_ * Copying action generators from actionlib to actionlib_msgs * updating review status * Updating actionlib_msgs comments (`#3003 `_) * filling out manifest * Documenting GoalStatus message * Forgot to commit files to actionlib_msgs * Moving actionlib messages into common_msgs/actionlib_msgs. Trac `#2504 `_ ros-common-msgs-1.12.7/actionlib_msgs/CMakeLists.txt000066400000000000000000000012151337176563300224140ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(actionlib_msgs) find_package(catkin REQUIRED COMPONENTS message_generation std_msgs) add_message_files( DIRECTORY msg FILES GoalID.msg GoalStatus.msg GoalStatusArray.msg) generate_messages(DEPENDENCIES std_msgs) catkin_package( CATKIN_DEPENDS message_runtime std_msgs CFG_EXTRAS actionlib_msgs-extras.cmake) # install the .action -> .msg generator catkin_install_python(PROGRAMS scripts/genaction.py DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) # install the legacy rosbuild cmake support install(FILES cmake/actionbuild.cmake DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/cmake) ros-common-msgs-1.12.7/actionlib_msgs/cmake/000077500000000000000000000000001337176563300207355ustar00rootroot00000000000000ros-common-msgs-1.12.7/actionlib_msgs/cmake/actionbuild.cmake000066400000000000000000000065061337176563300242430ustar00rootroot00000000000000# THIS FILE CANNOT BE MOVED. Users include it like so: # rosbuild_find_ros_package(actionlib_msgs) # include(${actionlib_msgs_PACKAGE_PATH}/cmake/actionbuild.cmake) macro(get_actions actionvar) file(GLOB _action_files RELATIVE "${PROJECT_SOURCE_DIR}/action" "${PROJECT_SOURCE_DIR}/action/*.action") message(STATUS "Action Files:" ${_action_files}) foreach(_action ${_action_files}) if(${_action} MATCHES "^[^\\.].*\\.action$") list(APPEND ${actionvar} ${_action}) endif(${_action} MATCHES "^[^\\.].*\\.action$") endforeach(_action) endmacro(get_actions) macro(genaction) if(ROSBUILD_init_called) message(FATAL_ERROR "genaction() cannot be called after rosbuild_init(), please change the order in your CMakeLists.txt file.") endif(ROSBUILD_init_called) get_actions(_actionlist) set(_autogen "") set(_autogen_msg_list "") foreach(_action ${_actionlist}) message(STATUS "Generating Messages for Action" ${_action}) #construct the path to the .action file set(_input ${PROJECT_SOURCE_DIR}/action/${_action}) string(REPLACE ".action" "" _action_bare ${_action}) # get path to action generator script find_package(catkin REQUIRED COMPONENTS actionlib_msgs) #We have to do this because message generation assumes filenames without full paths set(_base_output_action ${_action_bare}Action.msg) set(_base_output_goal ${_action_bare}Goal.msg) set(_base_output_action_goal ${_action_bare}ActionGoal.msg) set(_base_output_result ${_action_bare}Result.msg) set(_base_output_action_result ${_action_bare}ActionResult.msg) set(_base_output_feedback ${_action_bare}Feedback.msg) set(_base_output_action_feedback ${_action_bare}ActionFeedback.msg) set(_output_action ${PROJECT_SOURCE_DIR}/msg/${_base_output_action}) set(_output_goal ${PROJECT_SOURCE_DIR}/msg/${_base_output_goal}) set(_output_action_goal ${PROJECT_SOURCE_DIR}/msg/${_base_output_action_goal}) set(_output_result ${PROJECT_SOURCE_DIR}/msg/${_base_output_result}) set(_output_action_result ${PROJECT_SOURCE_DIR}/msg/${_base_output_action_result}) set(_output_feedback ${PROJECT_SOURCE_DIR}/msg/${_base_output_feedback}) set(_output_action_feedback ${PROJECT_SOURCE_DIR}/msg/${_base_output_action_feedback}) message(STATUS ${_output_action}) add_custom_command( OUTPUT ${_output_action} ${_output_goal} ${_output_action_goal} ${_output_result} ${_output_action_result} ${_output_feedback} ${_output_action_feedback} COMMAND ${GENACTION_BIN} ${_input} -o ${PROJECT_SOURCE_DIR}/msg DEPENDS ${_input} ${GENACTION_BIN} ${ROS_MANIFEST_LIST} ) list(APPEND _autogen ${_output_action} ${_output_goal} ${_output_action_goal} ${_output_result} ${_output_action_result} ${_output_feedback} ${_output_action_feedback}) 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}) endforeach(_action) # Create a target that depends on the union of all the autogenerated files add_custom_target(ROSBUILD_genaction_msgs ALL DEPENDS ${_autogen}) add_custom_target(rosbuild_premsgsrvgen) add_dependencies(rosbuild_premsgsrvgen ROSBUILD_genaction_msgs) rosbuild_add_generated_msgs(${_autogen_msg_list}) endmacro(genaction) ros-common-msgs-1.12.7/actionlib_msgs/cmake/actionlib_msgs-extras.cmake.em000066400000000000000000000054511337176563300266450ustar00rootroot00000000000000# need genmsg for _prepend_path() find_package(genmsg REQUIRED) include(CMakeParseArguments) @[if DEVELSPACE]@ # program in develspace set(GENACTION_BIN "@(CMAKE_CURRENT_SOURCE_DIR)/scripts/genaction.py") @[else]@ # program in installspace set(GENACTION_BIN "${actionlib_msgs_DIR}/../../../@(CATKIN_PACKAGE_BIN_DESTINATION)/genaction.py") @[end if]@ macro(add_action_files) cmake_parse_arguments(ARG "NOINSTALL" "DIRECTORY" "FILES" ${ARGN}) if(ARG_UNPARSED_ARGUMENTS) message(FATAL_ERROR "add_action_files() called with unused arguments: ${ARG_UNPARSED_ARGUMENTS}") endif() if(NOT ARG_DIRECTORY) set(ARG_DIRECTORY "action") endif() if(NOT IS_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR}/${ARG_DIRECTORY}) message(FATAL_ERROR "add_action_files() directory not found: ${CMAKE_CURRENT_SOURCE_DIR}/${ARG_DIRECTORY}") endif() # if FILES are not passed search action files in the given directory # note: ARGV is not variable, so it can not be passed to list(FIND) directly set(_argv ${ARGV}) list(FIND _argv "FILES" _index) if(_index EQUAL -1) file(GLOB ARG_FILES RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}/${ARG_DIRECTORY}" "${CMAKE_CURRENT_SOURCE_DIR}/${ARG_DIRECTORY}/*.action") list(SORT ARG_FILES) endif() _prepend_path(${CMAKE_CURRENT_SOURCE_DIR}/${ARG_DIRECTORY} "${ARG_FILES}" FILES_W_PATH) list(APPEND ${PROJECT_NAME}_ACTION_FILES ${FILES_W_PATH}) foreach(file ${FILES_W_PATH}) assert_file_exists(${file} "action file not found") endforeach() if(NOT ARG_NOINSTALL) install(FILES ${FILES_W_PATH} DESTINATION share/${PROJECT_NAME}/${ARG_DIRECTORY}) endif() foreach(actionfile ${FILES_W_PATH}) if(NOT CATKIN_DEVEL_PREFIX) message(FATAL_ERROR "Assertion failed: 'CATKIN_DEVEL_PREFIX' is not set") endif() get_filename_component(ACTION_SHORT_NAME ${actionfile} NAME_WE) set(MESSAGE_DIR ${CATKIN_DEVEL_PREFIX}/share/${PROJECT_NAME}/msg) set(OUTPUT_FILES ${ACTION_SHORT_NAME}Action.msg ${ACTION_SHORT_NAME}ActionGoal.msg ${ACTION_SHORT_NAME}ActionResult.msg ${ACTION_SHORT_NAME}ActionFeedback.msg ${ACTION_SHORT_NAME}Goal.msg ${ACTION_SHORT_NAME}Result.msg ${ACTION_SHORT_NAME}Feedback.msg) _prepend_path(${MESSAGE_DIR}/ "${OUTPUT_FILES}" OUTPUT_FILES_W_PATH) message(STATUS "Generating .msg files for action ${PROJECT_NAME}/${ACTION_SHORT_NAME} ${actionfile}") stamp(${actionfile}) if(NOT CATKIN_ENV) message(FATAL_ERROR "Assertion failed: 'CATKIN_ENV' is not set") endif() if(${actionfile} IS_NEWER_THAN ${MESSAGE_DIR}/${ACTION_SHORT_NAME}Action.msg) safe_execute_process(COMMAND ${CATKIN_ENV} ${PYTHON_EXECUTABLE} ${GENACTION_BIN} ${actionfile} -o ${MESSAGE_DIR}) endif() add_message_files( BASE_DIR ${MESSAGE_DIR} FILES ${OUTPUT_FILES}) endforeach() endmacro() ros-common-msgs-1.12.7/actionlib_msgs/msg/000077500000000000000000000000001337176563300204435ustar00rootroot00000000000000ros-common-msgs-1.12.7/actionlib_msgs/msg/GoalID.msg000066400000000000000000000005161337176563300222540ustar00rootroot00000000000000# The stamp should store the time at which this goal was requested. # It is used by an action server when it tries to preempt all # goals that were requested before a certain time time stamp # The id provides a way to associate feedback and # result message with specific goal requests. The id # specified must be unique. string id ros-common-msgs-1.12.7/actionlib_msgs/msg/GoalStatus.msg000066400000000000000000000031321337176563300232400ustar00rootroot00000000000000GoalID goal_id uint8 status uint8 PENDING = 0 # The goal has yet to be processed by the action server uint8 ACTIVE = 1 # The goal is currently being processed by the action server uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing # and has since completed its execution (Terminal State) uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State) uint8 ABORTED = 4 # The goal was aborted during execution by the action server due # to some failure (Terminal State) uint8 REJECTED = 5 # The goal was rejected by the action server without being processed, # because the goal was unattainable or invalid (Terminal State) uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing # and has not yet completed execution uint8 RECALLING = 7 # The goal received a cancel request before it started executing, # but the action server has not yet confirmed that the goal is canceled uint8 RECALLED = 8 # The goal received a cancel request before it started executing # and was successfully cancelled (Terminal State) uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be # sent over the wire by an action server #Allow for the user to associate a string with GoalStatus for debugging string text ros-common-msgs-1.12.7/actionlib_msgs/msg/GoalStatusArray.msg000066400000000000000000000001771337176563300242450ustar00rootroot00000000000000# Stores the statuses for goals that are currently being tracked # by an action server Header header GoalStatus[] status_list ros-common-msgs-1.12.7/actionlib_msgs/package.xml000066400000000000000000000016431337176563300217760ustar00rootroot00000000000000 actionlib_msgs 1.12.7 actionlib_msgs defines the common messages to interact with an action server and an action client. For full documentation of the actionlib API see the actionlib package. Tully Foote BSD http://wiki.ros.org/actionlib_msgs Vijay Pradeep catkin message_generation std_msgs message_generation message_runtime std_msgs ros-common-msgs-1.12.7/actionlib_msgs/scripts/000077500000000000000000000000001337176563300213445ustar00rootroot00000000000000ros-common-msgs-1.12.7/actionlib_msgs/scripts/genaction.py000077500000000000000000000111031337176563300236640ustar00rootroot00000000000000#! /usr/bin/env python # Copyright (c) 2009, Willow Garage, Inc. # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above copyright # notice, this list of conditions and the following disclaimer in the # documentation and/or other materials provided with the distribution. # * Neither the name of the Willow Garage, Inc. nor the names of its # contributors may be used to endorse or promote products derived from # this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. # Author: Stuart Glaser import sys try: from cStringIO import StringIO except ImportError: from io import StringIO import re import os, os.path import errno from optparse import OptionParser IODELIM = '---' AUTOGEN="# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======\n" class ActionSpecException(Exception): pass def parse_action_spec(text, package_context = ''): pieces = [StringIO()] for l in text.split('\n'): if l.startswith(IODELIM): pieces.append(StringIO()) else: pieces[-1].write(l + '\n') return [p.getvalue() for p in pieces] def write_file(filename, text): f = open(filename, 'w') f.write(text) f.close() def main(): parser = OptionParser("Actionlib generator") parser.add_option('-o', dest='output_dir', help='output directory') (options, args) = parser.parse_args(sys.argv) pkg = os.path.abspath(sys.argv[1]) filename = sys.argv[2] output_dir = options.output_dir # Try to make the directory, but silently continue if it already exists try: os.makedirs(output_dir) except OSError as e: if e.errno == errno.EEXIST: pass else: raise action_file = args[1] if not action_file.endswith('.action'): print("The file specified has the wrong extension. It must end in .action") else: filename = action_file f = open(filename) action_spec = f.read() f.close() name = os.path.basename(filename)[:-7] print("Generating for action %s" % name) pieces = parse_action_spec(action_spec) if len(pieces) != 3: raise ActionSpecException("%s: wrong number of pieces, %d"%(filename,len(pieces))) goal, result, feedback = pieces action_msg = AUTOGEN + """ %sActionGoal action_goal %sActionResult action_result %sActionFeedback action_feedback """ % (name, name, name) goal_msg = AUTOGEN + goal action_goal_msg = AUTOGEN + """ Header header actionlib_msgs/GoalID goal_id %sGoal goal """ % name result_msg = AUTOGEN + result action_result_msg = AUTOGEN + """ Header header actionlib_msgs/GoalStatus status %sResult result """ % name feedback_msg = AUTOGEN + feedback action_feedback_msg = AUTOGEN + """ Header header actionlib_msgs/GoalStatus status %sFeedback feedback """ % name write_file(os.path.join(output_dir, "%sAction.msg"%name), action_msg) write_file(os.path.join(output_dir, "%sGoal.msg"%name), goal_msg) write_file(os.path.join(output_dir, "%sActionGoal.msg"%name), action_goal_msg) write_file(os.path.join(output_dir, "%sResult.msg"%name), result_msg) write_file(os.path.join(output_dir, "%sActionResult.msg"%name), action_result_msg) write_file(os.path.join(output_dir, "%sFeedback.msg"%name), feedback_msg) write_file(os.path.join(output_dir, "%sActionFeedback.msg"%name), action_feedback_msg) if __name__ == '__main__': main() ros-common-msgs-1.12.7/common_msgs/000077500000000000000000000000001337176563300172015ustar00rootroot00000000000000ros-common-msgs-1.12.7/common_msgs/CHANGELOG.rst000066400000000000000000000042551337176563300212300ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package common_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.12.7 (2018-11-06) ------------------- 1.12.6 (2018-05-03) ------------------- 1.12.5 (2016-09-30) ------------------- 1.12.4 (2016-02-22) ------------------- 1.12.3 (2015-04-20) ------------------- 1.12.2 (2015-03-21) ------------------- 1.12.1 (2015-03-17) ------------------- * updating outdated urls. fixes `#52 `_. * Contributors: Tully Foote 1.12.0 (2014-12-29) ------------------- 1.11.6 (2014-11-04) ------------------- 1.11.5 (2014-10-27) ------------------- 1.11.4 (2014-06-19) ------------------- 1.11.3 (2014-05-07) ------------------- 1.11.2 (2014-04-24) ------------------- 1.11.1 (2014-04-16) ------------------- 1.11.0 (2014-03-04) ------------------- 1.10.6 (2014-02-27) ------------------- 1.10.5 (2014-02-25) ------------------- 1.10.4 (2014-02-18) ------------------- 1.10.3 (2014-01-07) ------------------- 1.10.2 (2013-08-19) ------------------- 1.10.1 (2013-08-16) ------------------- 1.10.0 (2013-07-13) ------------------- 1.9.16 (2013-05-21) ------------------- * add buildtool dep on catkin for metapackage * update email in package.xml 1.9.15 (2013-03-08) ------------------- * add CMakeLists.txt for metapackage 1.9.14 (2013-01-19) ------------------- 1.9.13 (2013-01-13) ------------------- 1.9.12 (2013-01-02) ------------------- 1.9.11 (2012-12-17) ------------------- 1.9.10 (2012-12-13) ------------------- 1.9.9 (2012-11-22) ------------------ 1.9.8 (2012-11-14) ------------------ 1.9.7 (2012-10-30) ------------------ 1.9.6 (2012-10-18) ------------------ 1.9.5 (2012-09-28) ------------------ 1.9.4 (2012-09-27 18:06) ------------------------ * fix dependency name 1.9.3 (2012-09-27 17:39) ------------------------ * cleanup * cleaned up package.xml files * fixed dependencies and more * updated to latest catkin: created package.xmls, updated CmakeLists.txt 1.9.2 (2012-09-05) ------------------ 1.9.1 (2012-09-04) ------------------ 1.9.0 (2012-08-29) ------------------ 1.8.13 (2012-07-26 18:34:15 +0000) ---------------------------------- 1.8.8 (2012-06-12 22:36) ------------------------ ros-common-msgs-1.12.7/common_msgs/CMakeLists.txt000066400000000000000000000001561337176563300217430ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(common_msgs) find_package(catkin REQUIRED) catkin_metapackage() ros-common-msgs-1.12.7/common_msgs/package.xml000066400000000000000000000024061337176563300213200ustar00rootroot00000000000000 common_msgs 1.12.7 common_msgs contains messages that are widely used by other ROS packages. These includes messages for actions (actionlib_msgs), diagnostics (diagnostic_msgs), geometric primitives (geometry_msgs), robot navigation (nav_msgs), and common sensors (sensor_msgs), such as laser range finders, cameras, point clouds. Tully Foote BSD http://wiki.ros.org/common_msgs catkin actionlib_msgs diagnostic_msgs geometry_msgs nav_msgs sensor_msgs shape_msgs stereo_msgs trajectory_msgs visualization_msgs ros-common-msgs-1.12.7/diagnostic_msgs/000077500000000000000000000000001337176563300200355ustar00rootroot00000000000000ros-common-msgs-1.12.7/diagnostic_msgs/CHANGELOG.rst000066400000000000000000000105161337176563300220610ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package diagnostic_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.12.7 (2018-11-06) ------------------- 1.12.6 (2018-05-03) ------------------- 1.12.5 (2016-09-30) ------------------- 1.12.4 (2016-02-22) ------------------- * diagnostic_msgs: Add messages for service used to add diagnostics to aggregator * Contributors: Michal Staniaszek 1.12.3 (2015-04-20) ------------------- 1.12.2 (2015-03-21) ------------------- 1.12.1 (2015-03-17) ------------------- * updating outdated urls. fixes `#52 `_. * Contributors: Tully Foote 1.12.0 (2014-12-29) ------------------- 1.11.6 (2014-11-04) ------------------- 1.11.5 (2014-10-27) ------------------- 1.11.4 (2014-06-19) ------------------- 1.11.3 (2014-05-07) ------------------- * Export architecture_independent flag in package.xml * Contributors: Scott K Logan 1.11.2 (2014-04-24) ------------------- * Add STALE to DiagnosticStatus level enum * Contributors: Austin 1.11.1 (2014-04-16) ------------------- 1.11.0 (2014-03-04) ------------------- 1.10.6 (2014-02-27) ------------------- 1.10.5 (2014-02-25) ------------------- 1.10.4 (2014-02-18) ------------------- 1.10.3 (2014-01-07) ------------------- 1.10.2 (2013-08-19) ------------------- 1.10.1 (2013-08-16) ------------------- 1.10.0 (2013-07-13) ------------------- 1.9.16 (2013-05-21) ------------------- * update email in package.xml 1.9.15 (2013-03-08) ------------------- 1.9.14 (2013-01-19) ------------------- 1.9.13 (2013-01-13) ------------------- 1.9.12 (2013-01-02) ------------------- 1.9.11 (2012-12-17) ------------------- * modified dep type of catkin 1.9.10 (2012-12-13) ------------------- * add missing downstream depend * switched from langs to message_* packages 1.9.9 (2012-11-22) ------------------ 1.9.8 (2012-11-14) ------------------ 1.9.7 (2012-10-30) ------------------ * fix catkin function order 1.9.6 (2012-10-18) ------------------ * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 1.9.5 (2012-09-28) ------------------ 1.9.4 (2012-09-27 18:06) ------------------------ 1.9.3 (2012-09-27 17:39) ------------------------ * cleanup * updated to latest catkin * fixed dependencies and more * updated to latest catkin: created package.xmls, updated CmakeLists.txt 1.9.2 (2012-09-05) ------------------ * updated pkg-config in manifest.xml 1.9.1 (2012-09-04) ------------------ * use install destination variables, removed manual installation of manifests 1.9.0 (2012-08-29) ------------------ 1.8.13 (2012-07-26 18:34:15 +0000) ---------------------------------- 1.8.8 (2012-06-12 22:36) ------------------------ * removed obsolete catkin tag from manifest files * adding manifest exports * removed depend, added catkin * 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 * common_msgs: removing migration rules as all are over a year old * bye bye vestigial MSG_DIRS * diagnostic_msgs: catkin'd * adios rosbuild2 in manifest.xml * missing dependencies * updating bagmigration exports * rosbuild2 taking shape * removing all the extra exports * Added Ubuntu platform tags to manifest * fixed manifest description * Remove use of deprecated rosbuild macros * changing review status * adding comment about stability for doc review * fixing link and wrapping lines * updated description and url * filling out description * documenting DiagnosticStatus and DiagnosticArray. setting proper constants for level of operation. bag migrations passes (incorrectly) ticketing Jeremy * Changing naming of bag migration rules. * Removing cross-stack dependency of test_common_msgs on pr2_msgs, and fixing diagnostic_msgs migration rules due to change in KeyValue. * Change KeyValue to actually be key/value * Adding more migration rule tests and fixing assorted rules. * fixing through diagnostic_updater * Fix DiagnosticStatus * removing DiagnosticString and DiagnosticValue and last few references to them `#1903 `_ * Changed DiagnosticMessage to DiagnosticArray * adding KeyValue for Blaise --Tully * Changed DiagnosticValue to KeyValue * merging in the changes to messages see ros-users email. THis is about half the common_msgs API changes * populating common_msgs ros-common-msgs-1.12.7/diagnostic_msgs/CMakeLists.txt000066400000000000000000000006421337176563300225770ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(diagnostic_msgs) find_package(catkin REQUIRED COMPONENTS message_generation std_msgs) add_message_files( DIRECTORY msg FILES DiagnosticArray.msg DiagnosticStatus.msg KeyValue.msg) add_service_files( DIRECTORY srv FILES AddDiagnostics.srv SelfTest.srv) generate_messages(DEPENDENCIES std_msgs) catkin_package(CATKIN_DEPENDS message_runtime std_msgs) ros-common-msgs-1.12.7/diagnostic_msgs/mainpage.dox000066400000000000000000000005141337176563300223320ustar00rootroot00000000000000/** \mainpage \htmlinclude manifest.html \b diagnostic_msgs is a package to hold the diagnostic messages These messages are used by the runtime diagnostics system. See the wiki at http://wiki.ros.org/diagnostic_msgs for a summary of the messages. And the diagnostic system is documented at http://wiki.ros.org/Diagnostics */ros-common-msgs-1.12.7/diagnostic_msgs/msg/000077500000000000000000000000001337176563300206235ustar00rootroot00000000000000ros-common-msgs-1.12.7/diagnostic_msgs/msg/DiagnosticArray.msg000066400000000000000000000002641337176563300244200ustar00rootroot00000000000000# This message is used to send diagnostic information about the state of the robot Header header #for timestamp DiagnosticStatus[] status # an array of components being reported onros-common-msgs-1.12.7/diagnostic_msgs/msg/DiagnosticStatus.msg000066400000000000000000000006521337176563300246260ustar00rootroot00000000000000# This message holds the status of an individual component of the robot. # # Possible levels of operations byte OK=0 byte WARN=1 byte ERROR=2 byte STALE=3 byte level # level of operation enumerated above string name # a description of the test/component reporting string message # a description of the status string hardware_id # a hardware unique string KeyValue[] values # an array of values associated with the status ros-common-msgs-1.12.7/diagnostic_msgs/msg/KeyValue.msg000066400000000000000000000001351337176563300230570ustar00rootroot00000000000000string key # what to label this value when viewing string value # a value to track over time ros-common-msgs-1.12.7/diagnostic_msgs/package.xml000066400000000000000000000021451337176563300221540ustar00rootroot00000000000000 diagnostic_msgs 1.12.7 This package holds the diagnostic messages which provide the standardized interface for the diagnostic and runtime monitoring systems in ROS. These messages are currently used by the diagnostics Stack, which provides libraries for simple ways to set and access the messages, as well as automated ways to process the diagnostic data. These messages are used for long term logging and will not be changed unless there is a very important reason. Tully Foote BSD http://wiki.ros.org/diagnostic_msgs Tully Foote catkin message_generation std_msgs message_runtime std_msgs ros-common-msgs-1.12.7/diagnostic_msgs/srv/000077500000000000000000000000001337176563300206475ustar00rootroot00000000000000ros-common-msgs-1.12.7/diagnostic_msgs/srv/AddDiagnostics.srv000066400000000000000000000026621337176563300242710ustar00rootroot00000000000000# This service is used as part of the process for loading analyzers at runtime, # and should be used by a loader script or program, not as a standalone service. # Information about dynamic addition of analyzers can be found at # http://wiki.ros.org/diagnostics/Tutorials/Adding%20Analyzers%20at%20Runtime # The load_namespace parameter defines the namespace where parameters for the # initialization of analyzers in the diagnostic aggregator have been loaded. The # value should be a global name (i.e. /my/name/space), not a relative # (my/name/space) or private (~my/name/space) name. Analyzers will not be added # if a non-global name is used. The call will also fail if the namespace # contains parameters that follow a namespace structure that does not conform to # that expected by the analyzer definitions. See # http://wiki.ros.org/diagnostics/Tutorials/Configuring%20Diagnostic%20Aggregators # and http://wiki.ros.org/diagnostics/Tutorials/Using%20the%20GenericAnalyzer # for examples of the structure of yaml files which are expected to have been # loaded into the namespace. string load_namespace --- # True if diagnostic aggregator was updated with new diagnostics, False # otherwise. A false return value means that either there is a bond in the # aggregator which already used the requested namespace, or the initialization # of analyzers failed. bool success # Message with additional information about the success or failure string message ros-common-msgs-1.12.7/diagnostic_msgs/srv/SelfTest.srv000066400000000000000000000000641337176563300231340ustar00rootroot00000000000000--- string id byte passed DiagnosticStatus[] status ros-common-msgs-1.12.7/geometry_msgs/000077500000000000000000000000001337176563300175445ustar00rootroot00000000000000ros-common-msgs-1.12.7/geometry_msgs/CHANGELOG.rst000066400000000000000000000177111337176563300215740ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package geometry_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.12.7 (2018-11-06) ------------------- * Add deprecation comment about Pose2D (`#130 `_) It started as unused and still isn't recommended. Followup to `#129 `_ * Contributors: Tully Foote 1.12.6 (2018-05-03) ------------------- 1.12.5 (2016-09-30) ------------------- * Fix spelling mistakes * Contributors: trorornmn 1.12.4 (2016-02-22) ------------------- * clarify the definition of a Vector3 * Contributors: Vincent Rabaud 1.12.3 (2015-04-20) ------------------- * geometry_msgs/InertiaStamped uses geometry_msgs/Inertia. * Contributors: Gayane Kazhoyan, Georg Bartels 1.12.2 (2015-03-21) ------------------- * Add Accel, AccelStamped, AccelWithCovariance, AccelWithCovarianceStamped message definitions * Add Inertia and InertiaStamped messages * Contributors: Jonathan Bohren, Paul Bovbel 1.12.1 (2015-03-17) ------------------- * updating outdated urls. fixes `#52 `_. * Contributors: Tully Foote 1.12.0 (2014-12-29) ------------------- 1.11.6 (2014-11-04) ------------------- 1.11.5 (2014-10-27) ------------------- 1.11.4 (2014-06-19) ------------------- 1.11.3 (2014-05-07) ------------------- * Export architecture_independent flag in package.xml * Contributors: Scott K Logan 1.11.2 (2014-04-24) ------------------- 1.11.1 (2014-04-16) ------------------- 1.11.0 (2014-03-04) ------------------- 1.10.6 (2014-02-27) ------------------- 1.10.5 (2014-02-25) ------------------- 1.10.4 (2014-02-18) ------------------- 1.10.3 (2014-01-07) ------------------- 1.10.2 (2013-08-19) ------------------- 1.10.1 (2013-08-16) ------------------- 1.10.0 (2013-07-13) ------------------- 1.9.16 (2013-05-21) ------------------- * update email in package.xml 1.9.15 (2013-03-08) ------------------- 1.9.14 (2013-01-19) ------------------- 1.9.13 (2013-01-13) ------------------- * fix spelling in comments (fix `#3194 `_) 1.9.12 (2013-01-02) ------------------- 1.9.11 (2012-12-17) ------------------- * modified dep type of catkin 1.9.10 (2012-12-13) ------------------- * add missing downstream depend * switched from langs to message_* packages 1.9.9 (2012-11-22) ------------------ 1.9.8 (2012-11-14) ------------------ 1.9.7 (2012-10-30) ------------------ * fix catkin function order 1.9.6 (2012-10-18) ------------------ * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 1.9.5 (2012-09-28) ------------------ 1.9.4 (2012-09-27 18:06) ------------------------ 1.9.3 (2012-09-27 17:39) ------------------------ * cleanup * cleaned up package.xml files * updated to latest catkin * fixed dependencies and more * updated to latest catkin: created package.xmls, updated CmakeLists.txt 1.9.2 (2012-09-05) ------------------ * updated pkg-config in manifest.xml 1.9.1 (2012-09-04) ------------------ * use install destination variables, removed manual installation of manifests 1.9.0 (2012-08-29) ------------------ 1.8.13 (2012-07-26 18:34:15 +0000) ---------------------------------- 1.8.8 (2012-06-12 22:36) ------------------------ * removed obsolete catkin tag from manifest files * removed unnecessary package name from some messages * adding manifest exports * removed depend, added catkin * 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 * install-related fixes * common_msgs: removing migration rules as all are over a year old * bye bye vestigial MSG_DIRS * geometry_msgs: getting rid of other build files * updated to new catkin_export_python macro * adios rosbuild2 in manifest.xml * catkin updates * catkin_project * Updated to work with new message generation macros * adios debian/ hello stack.yaml. (sketch/prototype/testing). * Getting standalone message generation working... w/o munging rosbuild2 * rosbuild2 tweaks * initial updating for new light message generation and wgbuild * missing dependencies * updating bagmigration exports * rosbuild2 taking shape * workaround bug #ros3018 until ros-1.2.3 comes out * removing all the extra exports * Added Ubuntu platform tags to manifest * Remove use of deprecated rosbuild macros * link to tf package as per doc review * doc reviewed status * wrapping manifest nicely * updated url and description * full migration rules * 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. * making covariance follow same convention as Pose * rotation representation was specified the wrong way in the message comment * Adding a stamped version of polygon * Adding comment to Polygon message * Adding migration rule from ParticleCloud to PoseArray * clearing API reviews for they've been through a bunch of them recently. * comments on all msgs except Polygon * removing PoseWithRates as it's deprecated. * Changing naming of bag migration rules. * Modifying migration rules for Odometry and WrenchStamped change of field names. * Adding actual migration rules for all of the tested common_msgs migrations. * undo of `#2270 `_, (.data for stamped). reverts r21133 * Adding migration rules to get migration tests to pass. * switching from PosewithRatesStamped to Odometry `#2277 `_ * Fixing some of the migration rules associated with unrolling of the .data change. * PoseWithCovarianceStamped::data -> PoseWithCovarianceStamped::pose * Reverse r21134, PointStamped::point->PointStamped::data * reverse QuaternionStamped::quaternion -> QuaternionStamped::data change * undoing r21137, keeping Vector3Stamped as was, but keeping in fix to door_handle_detector 'using' bug * Adding more migration rule tests and fixing assorted rules. * reverting r2118. Redoing `#2275 `_ `#2274 `_ to not go to 'data' standard * `#2271 `_ Vector3Stamped uses new standarization * PointStamped::point -> PointStamped::data (`#2276 `_) * new Stamped format `#2270 `_ * Changing migration rule for Twist to go to TwistStamped. * QuaternionStamped::quaternion -> QuaternionStamped::data (`#2278 `_) * `#2274 `_ `#2275 `_ updated to header/data * PoseWithCovariance->PoseWithCovarianceStamped PoseWithCovarianceStamped::pose_with_covariance -> PoseWithCovarianceStamped::data * 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 * Moved robot_msgs/Polygon3D to geometry_msgs/Polygon for ticket `#1310 `_ * moving PoseArray into geometry_msgs `#1907 `_ * removing header for this is a type for composing and doesn't stand on it's own to be transformed etc. * adding TwistWithCovariance `#2251 `_ * creating Wrench and WrenchStamped in geometry_msgs `#1935 `_ * adding unused Pose2D message as per API review `#2249 `_ * geometry_msgs: Documented that covariance uses fixed axis not euler angles. * merging in the changes to messages see ros-users email. THis is about half the common_msgs API changes ros-common-msgs-1.12.7/geometry_msgs/CMakeLists.txt000066400000000000000000000015011337176563300223010ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(geometry_msgs) find_package(catkin REQUIRED COMPONENTS message_generation std_msgs) add_message_files( DIRECTORY msg FILES Accel.msg AccelStamped.msg AccelWithCovariance.msg AccelWithCovarianceStamped.msg Inertia.msg InertiaStamped.msg Point.msg Point32.msg PointStamped.msg Polygon.msg PolygonStamped.msg Pose2D.msg Pose.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) generate_messages(DEPENDENCIES std_msgs) catkin_package(CATKIN_DEPENDS message_runtime std_msgs) ros-common-msgs-1.12.7/geometry_msgs/mainpage.dox000066400000000000000000000052741337176563300220510ustar00rootroot00000000000000/** \mainpage \htmlinclude manifest.html \b geometry_msgs is ... \section codeapi Code API \section rosapi ROS API */ros-common-msgs-1.12.7/geometry_msgs/msg/000077500000000000000000000000001337176563300203325ustar00rootroot00000000000000ros-common-msgs-1.12.7/geometry_msgs/msg/Accel.msg000066400000000000000000000001671337176563300220550ustar00rootroot00000000000000# This expresses acceleration in free space broken into its linear and angular parts. Vector3 linear Vector3 angular ros-common-msgs-1.12.7/geometry_msgs/msg/AccelStamped.msg000066400000000000000000000001231337176563300233630ustar00rootroot00000000000000# An accel with reference coordinate frame and timestamp Header header Accel accel ros-common-msgs-1.12.7/geometry_msgs/msg/AccelWithCovariance.msg000066400000000000000000000005121337176563300246760ustar00rootroot00000000000000# This expresses acceleration in free space with uncertainty. Accel accel # Row-major representation of the 6x6 covariance matrix # The orientation parameters use a fixed-axis representation. # In order, the parameters are: # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) float64[36] covariance ros-common-msgs-1.12.7/geometry_msgs/msg/AccelWithCovarianceStamped.msg000066400000000000000000000001741337176563300262200ustar00rootroot00000000000000# This represents an estimated accel with reference coordinate frame and timestamp. Header header AccelWithCovariance accel ros-common-msgs-1.12.7/geometry_msgs/msg/Inertia.msg000066400000000000000000000003531337176563300224360ustar00rootroot00000000000000# Mass [kg] float64 m # Center of mass [m] geometry_msgs/Vector3 com # Inertia Tensor [kg-m^2] # | ixx ixy ixz | # I = | ixy iyy iyz | # | ixz iyz izz | float64 ixx float64 ixy float64 ixz float64 iyy float64 iyz float64 izz ros-common-msgs-1.12.7/geometry_msgs/msg/InertiaStamped.msg000066400000000000000000000000361337176563300237520ustar00rootroot00000000000000Header header Inertia inertia ros-common-msgs-1.12.7/geometry_msgs/msg/Point.msg000066400000000000000000000001241337176563300221300ustar00rootroot00000000000000# This contains the position of a point in free space float64 x float64 y float64 z ros-common-msgs-1.12.7/geometry_msgs/msg/Point32.msg000066400000000000000000000005571337176563300223070ustar00rootroot00000000000000# This contains the position of a point in free space(with 32 bits of precision). # It is recommeded to use Point wherever possible instead of Point32. # # This recommendation is to promote interoperability. # # This message is designed to take up less space when sending # lots of points at once, as in the case of a PointCloud. float32 x float32 y float32 zros-common-msgs-1.12.7/geometry_msgs/msg/PointStamped.msg000066400000000000000000000001421337176563300234460ustar00rootroot00000000000000# This represents a Point with reference coordinate frame and timestamp Header header Point point ros-common-msgs-1.12.7/geometry_msgs/msg/Polygon.msg000066400000000000000000000001531337176563300224700ustar00rootroot00000000000000#A specification of a polygon where the first and last points are assumed to be connected Point32[] points ros-common-msgs-1.12.7/geometry_msgs/msg/PolygonStamped.msg000066400000000000000000000001501337176563300240030ustar00rootroot00000000000000# This represents a Polygon with reference coordinate frame and timestamp Header header Polygon polygon ros-common-msgs-1.12.7/geometry_msgs/msg/Pose.msg000066400000000000000000000001671337176563300217540ustar00rootroot00000000000000# A representation of pose in free space, composed of position and orientation. Point position Quaternion orientation ros-common-msgs-1.12.7/geometry_msgs/msg/Pose2D.msg000066400000000000000000000015441337176563300221420ustar00rootroot00000000000000# Deprecated # Please use the full 3D pose. # 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. # 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. # This expresses a position and orientation on a 2D manifold. float64 x float64 y float64 theta ros-common-msgs-1.12.7/geometry_msgs/msg/PoseArray.msg000066400000000000000000000001251337176563300227450ustar00rootroot00000000000000# An array of poses with a header for global reference. Header header Pose[] poses ros-common-msgs-1.12.7/geometry_msgs/msg/PoseStamped.msg000066400000000000000000000001171337176563300232650ustar00rootroot00000000000000# A Pose with reference coordinate frame and timestamp Header header Pose pose ros-common-msgs-1.12.7/geometry_msgs/msg/PoseWithCovariance.msg000066400000000000000000000005031337176563300245750ustar00rootroot00000000000000# This represents a pose in free space with uncertainty. Pose pose # Row-major representation of the 6x6 covariance matrix # The orientation parameters use a fixed-axis representation. # In order, the parameters are: # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) float64[36] covariance ros-common-msgs-1.12.7/geometry_msgs/msg/PoseWithCovarianceStamped.msg000066400000000000000000000001721337176563300261150ustar00rootroot00000000000000# This expresses an estimated pose with a reference coordinate frame and timestamp Header header PoseWithCovariance pose ros-common-msgs-1.12.7/geometry_msgs/msg/Quaternion.msg000066400000000000000000000001541337176563300231670ustar00rootroot00000000000000# This represents an orientation in free space in quaternion form. float64 x float64 y float64 z float64 w ros-common-msgs-1.12.7/geometry_msgs/msg/QuaternionStamped.msg000066400000000000000000000001651337176563300245070ustar00rootroot00000000000000# This represents an orientation with reference coordinate frame and timestamp. Header header Quaternion quaternion ros-common-msgs-1.12.7/geometry_msgs/msg/Transform.msg000066400000000000000000000001661337176563300230200ustar00rootroot00000000000000# This represents the transform between two coordinate frames in free space. Vector3 translation Quaternion rotation ros-common-msgs-1.12.7/geometry_msgs/msg/TransformStamped.msg000066400000000000000000000005211337176563300243310ustar00rootroot00000000000000# This expresses a transform from coordinate frame header.frame_id # to the coordinate frame child_frame_id # # This message is mostly used by the # tf package. # See its documentation for more information. Header header string child_frame_id # the frame id of the child frame Transform transform ros-common-msgs-1.12.7/geometry_msgs/msg/Twist.msg000066400000000000000000000001631337176563300221540ustar00rootroot00000000000000# This expresses velocity in free space broken into its linear and angular parts. Vector3 linear Vector3 angular ros-common-msgs-1.12.7/geometry_msgs/msg/TwistStamped.msg000066400000000000000000000001221337176563300234650ustar00rootroot00000000000000# A twist with reference coordinate frame and timestamp Header header Twist twist ros-common-msgs-1.12.7/geometry_msgs/msg/TwistWithCovariance.msg000066400000000000000000000005061337176563300250040ustar00rootroot00000000000000# This expresses velocity in free space with uncertainty. Twist twist # Row-major representation of the 6x6 covariance matrix # The orientation parameters use a fixed-axis representation. # In order, the parameters are: # (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis) float64[36] covariance ros-common-msgs-1.12.7/geometry_msgs/msg/TwistWithCovarianceStamped.msg000066400000000000000000000001741337176563300263230ustar00rootroot00000000000000# This represents an estimated twist with reference coordinate frame and timestamp. Header header TwistWithCovariance twist ros-common-msgs-1.12.7/geometry_msgs/msg/Vector3.msg000066400000000000000000000005761337176563300223770ustar00rootroot00000000000000# This represents a vector in free space. # It is only meant to represent a direction. Therefore, it does not # make sense to apply a translation to it (e.g., when applying a # generic rigid transformation to a Vector3, tf2 will only apply the # rotation). If you want your data to be translatable too, use the # geometry_msgs/Point message instead. float64 x float64 y float64 zros-common-msgs-1.12.7/geometry_msgs/msg/Vector3Stamped.msg000066400000000000000000000001471337176563300237070ustar00rootroot00000000000000# This represents a Vector3 with reference coordinate frame and timestamp Header header Vector3 vector ros-common-msgs-1.12.7/geometry_msgs/msg/Wrench.msg000066400000000000000000000001651337176563300222720ustar00rootroot00000000000000# This represents force in free space, separated into # its linear and angular parts. Vector3 force Vector3 torque ros-common-msgs-1.12.7/geometry_msgs/msg/WrenchStamped.msg000066400000000000000000000001251337176563300236040ustar00rootroot00000000000000# A wrench with reference coordinate frame and timestamp Header header Wrench wrench ros-common-msgs-1.12.7/geometry_msgs/package.xml000066400000000000000000000014321337176563300216610ustar00rootroot00000000000000 geometry_msgs 1.12.7 geometry_msgs provides messages for common geometric primitives such as points, vectors, and poses. These primitives are designed to provide a common data type and facilitate interoperability throughout the system. Tully Foote BSD http://wiki.ros.org/geometry_msgs Tully Foote catkin message_generation std_msgs message_runtime std_msgs ros-common-msgs-1.12.7/nav_msgs/000077500000000000000000000000001337176563300164755ustar00rootroot00000000000000ros-common-msgs-1.12.7/nav_msgs/CHANGELOG.rst000066400000000000000000000226511337176563300205240ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package nav_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.12.7 (2018-11-06) ------------------- 1.12.6 (2018-05-03) ------------------- 1.12.5 (2016-09-30) ------------------- 1.12.4 (2016-02-22) ------------------- 1.12.3 (2015-04-20) ------------------- 1.12.2 (2015-03-21) ------------------- * change type of initial_pose in SetMap service to PoseWithCovarianceStamped * Contributors: Stephan Wirth 1.12.1 (2015-03-17) ------------------- * updating outdated urls. fixes `#52 `_. * Adds a SetMap service message to support swap maps functionality in amcl * Contributors: Tully Foote, liz-murphy 1.12.0 (2014-12-29) ------------------- 1.11.6 (2014-11-04) ------------------- 1.11.5 (2014-10-27) ------------------- 1.11.4 (2014-06-19) ------------------- 1.11.3 (2014-05-07) ------------------- * Export architecture_independent flag in package.xml * Contributors: Scott K Logan 1.11.2 (2014-04-24) ------------------- 1.11.1 (2014-04-16) ------------------- 1.11.0 (2014-03-04) ------------------- 1.10.6 (2014-02-27) ------------------- 1.10.5 (2014-02-25) ------------------- 1.10.4 (2014-02-18) ------------------- 1.10.3 (2014-01-07) ------------------- 1.10.2 (2013-08-19) ------------------- 1.10.1 (2013-08-16) ------------------- 1.10.0 (2013-07-13) ------------------- 1.9.16 (2013-05-21) ------------------- * added action definition for getting maps * update email in package.xml 1.9.15 (2013-03-08) ------------------- 1.9.14 (2013-01-19) ------------------- 1.9.13 (2013-01-13) ------------------- 1.9.12 (2013-01-02) ------------------- 1.9.11 (2012-12-17) ------------------- * modified dep type of catkin 1.9.10 (2012-12-13) ------------------- * add missing downstream depend * switched from langs to message_* packages 1.9.9 (2012-11-22) ------------------ 1.9.8 (2012-11-14) ------------------ 1.9.7 (2012-10-30) ------------------ * fix catkin function order 1.9.6 (2012-10-18) ------------------ * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 1.9.5 (2012-09-28) ------------------ 1.9.4 (2012-09-27 18:06) ------------------------ 1.9.3 (2012-09-27 17:39) ------------------------ * cleanup * cleaned up package.xml files * updated to latest catkin * fixed dependencies and more * updated to latest catkin: created package.xmls, updated CmakeLists.txt 1.9.2 (2012-09-05) ------------------ * updated pkg-config in manifest.xml 1.9.1 (2012-09-04) ------------------ * use install destination variables, removed manual installation of manifests 1.9.0 (2012-08-29) ------------------ * updated to current catkin 1.8.13 (2012-07-26 18:34:15 +0000) ---------------------------------- 1.8.8 (2012-06-12 22:36) ------------------------ * make find_package REQUIRED * removed obsolete catkin tag from manifest files * fixed package dependencies for several common messages (fixed `#3956 `_) * adding manifest exports * removed depend, added catkin * 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 * common_msgs: removing migration rules as all are over a year old * bye bye vestigial MSG_DIRS * nav_msgs: getting rid of other build files and cleaning up * common_msgs: starting catkin conversion * adios rosbuild2 in manifest.xml * catkin updates * catkin_project * Updated to work with new message generation macros * More tweaking for standalone message generation * Getting standalone message generation working... w/o munging rosbuild2 * more rosbuild2 hacking * missing dependencies * updating bagmigration exports * rosbuild2 taking shape * removing old exports ros`#2292 `_ * Added Ubuntu platform tags to manifest * Adding a start pose to the GetPlan service * Remove use of deprecated rosbuild macros * Fixing migration rules for nav_msgs. * Changed byte to int8, in response to map_server doc review * changing review status * adding documentation for `#2997 `_ * removing redundant range statements as per ticket:2997 * Adding documentation to the Odometry message to make things more clear * manifest update * updated description and url * full migration rules * adding child_frame_id as per discussion about odometry message * Adding a header to Path * Adding a header to the GridCells message * Adding a new GridCells message for displaying obstacles in nav_view and rviz * clearing API reviews for they've been through a bunch of them recently. * fixing stack name * Adding comments to path * documenting messages * Making odometry migration fail until we have worked out appropriate way to handle covariances. * Changing naming of bag migration rules. * Modifying migration rules for Odometry and WrenchStamped change of field names. * Adding actual migration rules for all of the tested common_msgs migrations. * `#2250 `_ getting rid of _with_covariance in Odometry fields * nav_msgs: added missing srv export * Adding migration rules to get migration tests to pass. * removing last of robot_msgs and all dependencies on it * moving Path from robot_msgs to nav_msgs `#2281 `_ * adding header to OccupancyGrid `#1906 `_ * 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 * moving PoseArray into geometry_msgs `#1907 `_ * fixing names * Removing header since there's already one in the pose and fixing message definition to have variable names * adding Odometry message as per API review and ticket:2250 * merging in the changes to messages see ros-users email. THis is about half the common_msgs API changes * Forgot to check in the services I added.... shoot * Moving StaticMap.srv to GetMap.srv and moving Plan.srv to GetPlan.srv, also moving them to nav_msgs and removing the nav_srvs package * Merging tha actionlib branch back into trunk r29135@att (orig r19792): eitanme | 2009-07-27 18:30:30 -0700 Creating a branch for actionlib.... hopefully for the last time r29137@att (orig r19794): eitanme | 2009-07-27 18:32:49 -0700 Changing ParticleCloud to PoseArray r29139@att (orig r19796): eitanme | 2009-07-27 18:33:42 -0700 Adding action definition to the rep r29148@att (orig r19805): eitanme | 2009-07-27 18:47:39 -0700 Some fixes... almost compiling r29165@att (orig r19822): eitanme | 2009-07-27 20:41:07 -0700 Macro version of the typedefs that compiles r29213@att (orig r19869): eitanme | 2009-07-28 11:49:10 -0700 Compling version of the ActionServer re-write complete with garbage collection, be default it will keep goals without goal handles for 5 seconds r29220@att (orig r19876): eitanme | 2009-07-28 12:06:06 -0700 Fix to make sure that transitions into preempting and recalling states actually happen r29254@att (orig r19888): eitanme | 2009-07-28 13:27:40 -0700 Forgot to actually call the cancel callback... addind a subscriber on the cancel topic r29267@att (orig r19901): eitanme | 2009-07-28 14:41:09 -0700 Adding text field to GoalStatus to allow users to throw some debugging information into the GoalStatus messages r29275@att (orig r19909): eitanme | 2009-07-28 15:43:49 -0700 Using tf remapping as I should've been doing for awhile r29277@att (orig r19911): eitanme | 2009-07-28 15:48:48 -0700 The navigation stack can now handle goals that aren't in the global frame. However, these goals will be transformed to the global frame at the time of reception, so for achieving them accurately the global frame of move_base should really be set to match the goals. r29299@att (orig r19933): stuglaser | 2009-07-28 17:08:10 -0700 Created genaction.py script to create the various messages that an action needs r29376@att (orig r20003): vijaypradeep | 2009-07-29 02:45:24 -0700 ActionClient is running. MoveBase ActionServer seems to be crashing r29409@att (orig r20033): vijaypradeep | 2009-07-29 11:57:54 -0700 Fixing bug with adding status trackers r29410@att (orig r20034): vijaypradeep | 2009-07-29 11:58:18 -0700 Changing from Release to Debug r29432@att (orig r20056): vijaypradeep | 2009-07-29 14:07:30 -0700 No longer building goal_manager_test.cpp r29472@att (orig r20090): vijaypradeep | 2009-07-29 17:04:14 -0700 Lots of Client-Side doxygen r29484@att (orig r20101): vijaypradeep | 2009-07-29 18:35:01 -0700 Adding to mainpage.dox r29487@att (orig r20104): eitanme | 2009-07-29 18:55:06 -0700 Removing file to help resolve merge I hope r29489@att (orig r20106): eitanme | 2009-07-29 19:00:07 -0700 Removing another file to try to resolve the branch r29492@att (orig r20108): eitanme | 2009-07-29 19:14:25 -0700 Again removing a file to get the merge working r29493@att (orig r20109): eitanme | 2009-07-29 19:34:45 -0700 Removing yet another file on which ssl negotiation fails r29500@att (orig r20116): eitanme | 2009-07-29 19:54:18 -0700 Fixing bug in genaction * moving MapMetaData and OccGrid into nav_msgs `#1303 `_ * created nav_msgs and moved ParticleCloud there `#1300 `_ ros-common-msgs-1.12.7/nav_msgs/CMakeLists.txt000066400000000000000000000010661337176563300212400ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(nav_msgs) find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation std_msgs actionlib_msgs) add_message_files( DIRECTORY msg FILES GridCells.msg MapMetaData.msg OccupancyGrid.msg Odometry.msg Path.msg) add_service_files( DIRECTORY srv FILES GetMap.srv GetPlan.srv SetMap.srv) add_action_files( FILES GetMap.action) generate_messages(DEPENDENCIES geometry_msgs std_msgs actionlib_msgs) catkin_package(CATKIN_DEPENDS geometry_msgs message_runtime std_msgs actionlib_msgs) ros-common-msgs-1.12.7/nav_msgs/action/000077500000000000000000000000001337176563300177525ustar00rootroot00000000000000ros-common-msgs-1.12.7/nav_msgs/action/GetMap.action000066400000000000000000000001321337176563300223220ustar00rootroot00000000000000# Get the map as a nav_msgs/OccupancyGrid --- nav_msgs/OccupancyGrid map --- # no feedbackros-common-msgs-1.12.7/nav_msgs/msg/000077500000000000000000000000001337176563300172635ustar00rootroot00000000000000ros-common-msgs-1.12.7/nav_msgs/msg/GridCells.msg000066400000000000000000000001611337176563300216410ustar00rootroot00000000000000#an array of cells in a 2D grid Header header float32 cell_width float32 cell_height geometry_msgs/Point[] cells ros-common-msgs-1.12.7/nav_msgs/msg/MapMetaData.msg000066400000000000000000000005661337176563300221200ustar00rootroot00000000000000# This hold basic information about the characterists of the OccupancyGrid # The time at which the map was loaded time map_load_time # The map resolution [m/cell] float32 resolution # Map width [cells] uint32 width # Map height [cells] uint32 height # The origin of the map [m, m, rad]. This is the real-world pose of the # cell (0,0) in the map. geometry_msgs/Pose originros-common-msgs-1.12.7/nav_msgs/msg/OccupancyGrid.msg000066400000000000000000000004431337176563300225260ustar00rootroot00000000000000# This represents a 2-D grid map, in which each cell represents the probability of # occupancy. Header header #MetaData for the map MapMetaData info # The map data, in row-major order, starting with (0,0). Occupancy # probabilities are in the range [0,100]. Unknown is -1. int8[] data ros-common-msgs-1.12.7/nav_msgs/msg/Odometry.msg000066400000000000000000000006011337176563300215720ustar00rootroot00000000000000# This represents an estimate of a position and velocity in free space. # The pose in this message should be specified in the coordinate frame given by header.frame_id. # The twist in this message should be specified in the coordinate frame given by the child_frame_id Header header string child_frame_id geometry_msgs/PoseWithCovariance pose geometry_msgs/TwistWithCovariance twist ros-common-msgs-1.12.7/nav_msgs/msg/Path.msg000066400000000000000000000001601337176563300206640ustar00rootroot00000000000000#An array of poses that represents a Path for a robot to follow Header header geometry_msgs/PoseStamped[] poses ros-common-msgs-1.12.7/nav_msgs/package.xml000066400000000000000000000015331337176563300206140ustar00rootroot00000000000000 nav_msgs 1.12.7 nav_msgs defines the common messages used to interact with the navigation stack. Tully Foote BSD http://wiki.ros.org/nav_msgs Tully Foote catkin geometry_msgs message_generation std_msgs actionlib_msgs geometry_msgs message_runtime std_msgs actionlib_msgs ros-common-msgs-1.12.7/nav_msgs/srv/000077500000000000000000000000001337176563300173075ustar00rootroot00000000000000ros-common-msgs-1.12.7/nav_msgs/srv/GetMap.srv000066400000000000000000000001111337176563300212110ustar00rootroot00000000000000# Get the map as a nav_msgs/OccupancyGrid --- nav_msgs/OccupancyGrid map ros-common-msgs-1.12.7/nav_msgs/srv/GetPlan.srv000066400000000000000000000005311337176563300213740ustar00rootroot00000000000000# Get a plan from the current position to the goal Pose # The start pose for the plan geometry_msgs/PoseStamped start # The final pose of the goal position geometry_msgs/PoseStamped goal # If the goal is obstructed, how many meters the planner can # relax the constraint in x and y before failing. float32 tolerance --- nav_msgs/Path plan ros-common-msgs-1.12.7/nav_msgs/srv/SetMap.srv000066400000000000000000000002201337176563300212260ustar00rootroot00000000000000# Set a new map together with an initial pose nav_msgs/OccupancyGrid map geometry_msgs/PoseWithCovarianceStamped initial_pose --- bool success ros-common-msgs-1.12.7/sensor_msgs/000077500000000000000000000000001337176563300172225ustar00rootroot00000000000000ros-common-msgs-1.12.7/sensor_msgs/CHANGELOG.rst000066400000000000000000000317341337176563300212530ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package sensor_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.12.7 (2018-11-06) ------------------- * Include sstream on header that needs i (`#131 `_) * included missing import for the read_points_list method (`#128 `_) * included missing import for the read_points_list method * Merge pull request `#127 `_ from ros-1/fix-typos * Merge pull request `#85 `_ from ros/missing_test_target_dependency fix missing test target dependency * Contributors: Dirk Thomas, Jasper, Kuang Fangjun, Tully Foote, chapulina 1.12.6 (2018-05-03) ------------------- * Return default value to prevent missing return warning. * Add function to convert PointCloud2 to namedtuples Add new function read_points_list that converts a PointCloud2 to a list of named tuples. It works on top of read_points, which generates lists containing the values. In consequence read_points_list is slower than read_points. * Added equidistant distortion model const * Added test_depend on rosunit in sensor_msgs * fix catkin_lint warnings * add mingration rule, copied from common_msgs-1.6 * Add missing include for atoi. Fixes `#97 `_ * Contributors: 2scholz, Adam Allevato, Ivor Wanders, Kei Okada, Tully Foote, alexzzhu 1.12.5 (2016-09-30) ------------------- * Deal with abstract image encodings * Fix spelling mistakes * Fix year * Contributors: Jochen Sprickerhof, Kentaro Wada, trorornmn 1.12.4 (2016-02-22) ------------------- * added type mapping and support for different types of points in point clouds * remove boost dependency fixes `#81 `_ * adding a BatteryState message * fix iterator doc * remove warning due to anonymous namespace * Contributors: Sebastian Pütz, Tully Foote, Vincent Rabaud 1.12.3 (2015-04-20) ------------------- 1.12.2 (2015-03-21) ------------------- 1.12.1 (2015-03-17) ------------------- 1.12.0 (2014-12-29) ------------------- 1.11.6 (2014-11-04) ------------------- * Fix compilation with Clang * Contributors: jmtatsch 1.11.5 (2014-10-27) ------------------- * add a test for the operator+ fix The behavior of that operator also had to be fixed to return a proper child class * fix critical bug with operator+ * Contributors: Michael Ferguson, Vincent Rabaud 1.11.4 (2014-06-19) ------------------- * Fix bug caused by use of va_arg in argument list. * Contributors: Daniel Maturana 1.11.3 (2014-05-07) ------------------- * clean up documentation of sensor_msgs so that wiki generated doxygen is readable * Export architecture_independent flag in package.xml * Contributors: Michael Ferguson, Scott K Logan 1.11.2 (2014-04-24) ------------------- 1.11.1 (2014-04-16) ------------------- * fix missing include dirs for tests * Contributors: Dirk Thomas 1.11.0 (2014-03-04) ------------------- * add a PointCloud2 iterator and modifier * Contributors: Tully Foote, Vincent Rabaud 1.10.6 (2014-02-27) ------------------- 1.10.5 (2014-02-25) ------------------- 1.10.4 (2014-02-18) ------------------- * Fix roslib import for message module, remove roslib.load_manifest * Contributors: Bence Magyar 1.10.3 (2014-01-07) ------------------- * python 3 compatibility * line wrap Imu.msg comments 1.10.2 (2013-08-19) ------------------- * adding __init__.py `#11 `_ 1.10.1 (2013-08-16) ------------------- * setup.py for `#11 `_ * adding installation of point_cloud2.py to sensor_msgs fixes `#11 `_ 1.10.0 (2013-07-13) ------------------- * adding MultiDOFJointState message 1.9.16 (2013-05-21) ------------------- * update email in package.xml 1.9.15 (2013-03-08) ------------------- 1.9.14 (2013-01-19) ------------------- 1.9.13 (2013-01-13) ------------------- * YUV422 actually has an 8 bit depth 1.9.12 (2013-01-02) ------------------- * do not consider YUV422 to be a color anymore * added missing license header 1.9.11 (2012-12-17) ------------------- * modified dep type of catkin 1.9.10 (2012-12-13) ------------------- * add missing downstream depend * switched from langs to message_* packages 1.9.9 (2012-11-22) ------------------ * Added Low-Cost/Android Sensors reviewed messages * Updated comments to reflect REP 117 for fixed-distance rangers * Adding reviewed MultiEchoLaserScan message. 1.9.8 (2012-11-14) ------------------ 1.9.7 (2012-10-30) ------------------ * fix catkin function order 1.9.6 (2012-10-18) ------------------ * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro * fix the bad number of channels for YUV422 UYVY 1.9.5 (2012-09-28) ------------------ * fixed missing find genmsg 1.9.4 (2012-09-27 18:06) ------------------------ 1.9.3 (2012-09-27 17:39) ------------------------ * cleanup * add precision about YUV422 * add YUV422 to some functions * cleaned up package.xml files * updated to latest catkin * fixed dependencies and more * updated to latest catkin: created package.xmls, updated CmakeLists.txt 1.9.2 (2012-09-05) ------------------ * updated pkg-config in manifest.xml * updated catkin variables 1.9.1 (2012-09-04) ------------------ * use install destination variables, removed manual installation of manifests 1.9.0 (2012-08-29) ------------------ * update the docs 1.8.13 (2012-07-26 18:34:15 +0000) ---------------------------------- * made inline functions static inline * fix ODR violation and missing headers * moved c++ code from sensor_msgs to headers 1.8.8 (2012-06-12 22:36) ------------------------ * simplifying deps * make find_package REQUIRED * removed obsolete catkin tag from manifest files * fixed package dependency for another common message (`#3956 `_), removed unnecessary package name from another message * fixed package dependencies for several common messages (fixed `#3956 `_) * clarify NavSatFix message comments * normalize shared lib building, `#3838 `_ * adding TimeReference to build * TimeReference decl was invalid * adding point_cloud2 as reviewed at http://ros.org/wiki/sensor_msgs/Reviews/Python%20PointCloud2%20_API_Review * TimeReference msg as reviewed #ros-pkg5355 * install headers * adding manifest exports * fix boost-finding stuff * removed depend, added catkin * adding roscpp_core dependencies * 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 * install-related fixes * common_msgs: removing migration rules as all are over a year old * sensor_msgs: removing old octave support now that rosoct is gone * bye bye vestigial MSG_DIRS * sensor_msgs: getting rid of other build files * adios rosbuild2 in manifest.xml * catkin updates * catkin_project * Updated to work with new message generation macros * adios debian/ hello stack.yaml. (sketch/prototype/testing). * More tweaking for standalone message generation * Getting standalone message generation working... w/o munging rosbuild2 * more rosbuild2 hacking * rosbuild2 tweaks * missing dependencies * sensor_msgs: Added YUV422 image encoding constant. * adding in explicit ros/console.h include for ros macros now that ros::Message base class is gone * adding JoyFeedback and JoyFeedbackArray * updating manifest.xml * adding Joy.msg * Add image encodings for 16-bit Bayer, RGB, and BGR formats. Update isMono(), isAlpha(), isBayer(), etc. * rosbuild2 taking shape * sensor_msgs: Source-compatible corrections to fillImage signature. * sensor_msgs: Functions for distinguishing categories of encodings. From cv_bridge redesign API review. * applying patch to this method like josh did in r33966 in rviz * sensor_msgs (rep0104): Migration rules for CameraInfo, RegionOfInterest. * sensor_msgs (rep0104): Doc improvements for CameraInfo. * sensor_msgs (rep0104): Cleaned up PointCloud2 msg docs. Restored original meaning of 'no invalid points' to is_dense (`#4446 `_). * sensor_msgs (rep0104): Documented u,v channel semantics for PointCloud msg (`#4482 `_). * sensor_msgs (rep0104): Added distortion model string constants. * sensor_msgs (rep0104): Include guard for image_encodings.h. * sensor_msgs (rep0104): Applied changes to CameraInfo and RegionOfInterest messages. * Clarify frame of reference for NavSatFix position covariance. * Add new satellite navigation messages approved by GPS API review. * adding Range message as reviewed `#4488 `_ * adding missing file * cleaner fix for point_cloud_conversion definitions for `#4451 `_ * inlining implementation in header for `#4451 `_ * sensor_msgs: Fixed URL in CameraInfo.msg and indicated how to mark an uncalibrated camera. `#4105 `_ * removing all the extra exports * add units to message description * bug fix in PC->PC2 conversion * include guards for point_cloud_conversions.h `#4285 `_ * Added Ubuntu platform tags to manifest * added PointCloud2<->PointCloud conversion routines. * Updating link to camera calibration * updating message as per review http://www.ros.org/wiki/sensor_msgs/Reviews/2010-03-01%20PointCloud2_API_Review * sensor_msgs: Added size (number of elements for arrays) to PointField. * pushing the new PointCloud structure in trunk * Changed wording of angle convention for the LaserScan message. We are now specifying how angles are measured, not which way the laser spins. * Remove use of deprecated rosbuild macros * Added exporting of generated srv includes. * Added call to gen_srv now that there is a service. * Added the SetCameraInfo service. * octave image parsing function now handles all possible image format types * changing review status * adding JointState documentation ticket:3006 * Typo in comments * updated parsing routines for octave * Adding 1 more rule for migration point clouds and bringing test_common_msgs back from future. * Adding JointState migration rule. * replace pr2_mechanism_msgs::JointStates by new non-pr2-specific sensor_msgs::JointState. Door test passes * better documentation of the CameraInfo message * updated url * sensor_msgs: Added rule to migrate from old laser_scan/LaserScan. * sensor_msgs: Added string constants for bayer encodings. * clearing API reviews for they've been through a bunch of them recently. * Removed the Timestamp message. * Updating migration rules to better support the intermediate Image message that existed. * comments for sensor_msgs * Adding a CompressedImage migration rule. * Fixing robot_msgs references * Changing the ordering of fields within the new image message so that all meta information comes before the data block. * Migration of RawStereo message. * Migration rule for CameraInfo. * First cut at migration rules for images. * Moving stereo messages out of sensor_msgs to stereo/stereo_msgs * Getting rid of PixelEncoding since it is encompassed in Image message instead. * update to IMU message comments and defined semantics for covariance * Changing naming of bag migration rules. * Image message and CvBridge change * moving FillImage.h to fill_image.h for Jeremy * Adding image_encodings header/cpp, since genmsg_cpp doesn't actually support constant string values * fixing spelling * Message documentation * Switching IMU to sensor_msgs/Imu related to `#2277 `_ * adding IMU msg * Took out event_type field, as that would indeed make it more than a timestamp. * adding OpenCV doc comment * Rename rows,cols to height,width in Image message * Adding more migration rule tests and fixing assorted rules. * Added a timestamp message. (Will be used to track camera and perhaps some day hokuyo trigger times.) * sensor_msgs: Updates to CameraInfo, added pixel encoding and ROI. * New sensor_msgs::Image message * PointCloud: * pts -> points * chan -> channels ChannelFloat32: * vals -> values * sensor_msgs: Added explanation of reprojection matrix to StereoInfo. * sensor_msgs: Cleaned up CompressedImage. Updated image_publisher. Blacklisted jpeg. * merging in the changes to messages see ros-users email. THis is about half the common_msgs API changes * sensor_msgs: Comments to better describe CameraInfo and StereoInfo. * Renamed CamInfo message to CameraInfo. * sensor_msgs_processImage can now process empty images * * update openrave and sensor_msgs octave scripts * Image from image_msgs -> sensor_msgs `#1661 `_ * updating review status * moving LaserScan from laser_scan package to sensor_msgs package `#1254 `_ * populating common_msgs ros-common-msgs-1.12.7/sensor_msgs/CMakeLists.txt000066400000000000000000000023361337176563300217660ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(sensor_msgs) find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation std_msgs) # For point_cloud2.py catkin_python_setup() include_directories(include) add_message_files( DIRECTORY msg FILES 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) add_service_files( DIRECTORY srv FILES SetCameraInfo.srv) generate_messages(DEPENDENCIES geometry_msgs std_msgs) catkin_package( INCLUDE_DIRS include CATKIN_DEPENDS geometry_msgs message_runtime std_msgs) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} FILES_MATCHING PATTERN "*.h") install(DIRECTORY migration_rules DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) if (CATKIN_ENABLE_TESTING) add_subdirectory(test) endif() ros-common-msgs-1.12.7/sensor_msgs/include/000077500000000000000000000000001337176563300206455ustar00rootroot00000000000000ros-common-msgs-1.12.7/sensor_msgs/include/sensor_msgs/000077500000000000000000000000001337176563300232075ustar00rootroot00000000000000ros-common-msgs-1.12.7/sensor_msgs/include/sensor_msgs/distortion_models.h000066400000000000000000000041011337176563300271150ustar00rootroot00000000000000 /********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ #ifndef SENSOR_MSGS_DISTORTION_MODELS_H #define SENSOR_MSGS_DISTORTION_MODELS_H #include namespace sensor_msgs { namespace distortion_models { const std::string PLUMB_BOB = "plumb_bob"; const std::string RATIONAL_POLYNOMIAL = "rational_polynomial"; const std::string EQUIDISTANT = "equidistant"; } } #endif ros-common-msgs-1.12.7/sensor_msgs/include/sensor_msgs/fill_image.h000066400000000000000000000047571337176563300254650ustar00rootroot00000000000000/********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2008, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ #ifndef FILLIMAGE_HH #define FILLIMAGE_HH #include "sensor_msgs/Image.h" #include "sensor_msgs/image_encodings.h" namespace sensor_msgs { static inline bool fillImage(Image& image, const std::string& encoding_arg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, const void* data_arg) { image.encoding = encoding_arg; image.height = rows_arg; image.width = cols_arg; image.step = step_arg; size_t st0 = (step_arg * rows_arg); image.data.resize(st0); memcpy(&image.data[0], data_arg, st0); image.is_bigendian = 0; return true; } static inline void clearImage(Image& image) { image.data.resize(0); } } #endif ros-common-msgs-1.12.7/sensor_msgs/include/sensor_msgs/image_encodings.h000066400000000000000000000206701337176563300265000ustar00rootroot00000000000000 /********************************************************************* * Software License Agreement (BSD License) * * Copyright (c) 2009, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of the Willow Garage nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. *********************************************************************/ #ifndef SENSOR_MSGS_IMAGE_ENCODINGS_H #define SENSOR_MSGS_IMAGE_ENCODINGS_H #include #include #include namespace sensor_msgs { namespace image_encodings { const std::string RGB8 = "rgb8"; const std::string RGBA8 = "rgba8"; const std::string RGB16 = "rgb16"; const std::string RGBA16 = "rgba16"; const std::string BGR8 = "bgr8"; const std::string BGRA8 = "bgra8"; const std::string BGR16 = "bgr16"; const std::string BGRA16 = "bgra16"; const std::string MONO8="mono8"; const std::string MONO16="mono16"; // OpenCV CvMat types const std::string TYPE_8UC1="8UC1"; const std::string TYPE_8UC2="8UC2"; const std::string TYPE_8UC3="8UC3"; const std::string TYPE_8UC4="8UC4"; const std::string TYPE_8SC1="8SC1"; const std::string TYPE_8SC2="8SC2"; const std::string TYPE_8SC3="8SC3"; const std::string TYPE_8SC4="8SC4"; const std::string TYPE_16UC1="16UC1"; const std::string TYPE_16UC2="16UC2"; const std::string TYPE_16UC3="16UC3"; const std::string TYPE_16UC4="16UC4"; const std::string TYPE_16SC1="16SC1"; const std::string TYPE_16SC2="16SC2"; const std::string TYPE_16SC3="16SC3"; const std::string TYPE_16SC4="16SC4"; const std::string TYPE_32SC1="32SC1"; const std::string TYPE_32SC2="32SC2"; const std::string TYPE_32SC3="32SC3"; const std::string TYPE_32SC4="32SC4"; const std::string TYPE_32FC1="32FC1"; const std::string TYPE_32FC2="32FC2"; const std::string TYPE_32FC3="32FC3"; const std::string TYPE_32FC4="32FC4"; const std::string TYPE_64FC1="64FC1"; const std::string TYPE_64FC2="64FC2"; const std::string TYPE_64FC3="64FC3"; const std::string TYPE_64FC4="64FC4"; // Bayer encodings const std::string BAYER_RGGB8="bayer_rggb8"; const std::string BAYER_BGGR8="bayer_bggr8"; const std::string BAYER_GBRG8="bayer_gbrg8"; const std::string BAYER_GRBG8="bayer_grbg8"; const std::string BAYER_RGGB16="bayer_rggb16"; const std::string BAYER_BGGR16="bayer_bggr16"; const std::string BAYER_GBRG16="bayer_gbrg16"; const std::string BAYER_GRBG16="bayer_grbg16"; // Miscellaneous // This is the UYVY version of YUV422 codec http://www.fourcc.org/yuv.php#UYVY // with an 8-bit depth const std::string YUV422="yuv422"; // Prefixes for abstract image encodings const std::string ABSTRACT_ENCODING_PREFIXES[] = { "8UC", "8SC", "16UC", "16SC", "32SC", "32FC", "64FC"}; // Utility functions for inspecting an encoding string static inline bool isColor(const std::string& encoding) { return encoding == RGB8 || encoding == BGR8 || encoding == RGBA8 || encoding == BGRA8 || encoding == RGB16 || encoding == BGR16 || encoding == RGBA16 || encoding == BGRA16; } static inline bool isMono(const std::string& encoding) { return encoding == MONO8 || encoding == MONO16; } static inline bool isBayer(const std::string& encoding) { return encoding == BAYER_RGGB8 || encoding == BAYER_BGGR8 || encoding == BAYER_GBRG8 || encoding == BAYER_GRBG8 || encoding == BAYER_RGGB16 || encoding == BAYER_BGGR16 || encoding == BAYER_GBRG16 || encoding == BAYER_GRBG16; } static inline bool hasAlpha(const std::string& encoding) { return encoding == RGBA8 || encoding == BGRA8 || encoding == RGBA16 || encoding == BGRA16; } static inline int numChannels(const std::string& encoding) { // First do the common-case encodings if (encoding == MONO8 || encoding == MONO16) return 1; if (encoding == BGR8 || encoding == RGB8 || encoding == BGR16 || encoding == RGB16) return 3; if (encoding == BGRA8 || encoding == RGBA8 || encoding == BGRA16 || encoding == RGBA16) return 4; if (encoding == BAYER_RGGB8 || encoding == BAYER_BGGR8 || encoding == BAYER_GBRG8 || encoding == BAYER_GRBG8 || encoding == BAYER_RGGB16 || encoding == BAYER_BGGR16 || encoding == BAYER_GBRG16 || encoding == BAYER_GRBG16) return 1; // Now all the generic content encodings // TODO: Rewrite with regex when ROS supports C++11 for (size_t i=0; i < sizeof(ABSTRACT_ENCODING_PREFIXES) / sizeof(*ABSTRACT_ENCODING_PREFIXES); i++) { std::string prefix = ABSTRACT_ENCODING_PREFIXES[i]; if (encoding.substr(0, prefix.size()) != prefix) continue; if (encoding.size() == prefix.size()) return 1; // ex. 8UC -> 1 int n_channel = atoi(encoding.substr(prefix.size(), encoding.size() - prefix.size()).c_str()); // ex. 8UC5 -> 5 if (n_channel != 0) return n_channel; // valid encoding string } if (encoding == YUV422) return 2; throw std::runtime_error("Unknown encoding " + encoding); return -1; } static inline int bitDepth(const std::string& encoding) { if (encoding == MONO16) return 16; if (encoding == MONO8 || encoding == BGR8 || encoding == RGB8 || encoding == BGRA8 || encoding == RGBA8 || encoding == BAYER_RGGB8 || encoding == BAYER_BGGR8 || encoding == BAYER_GBRG8 || encoding == BAYER_GRBG8) return 8; if (encoding == MONO16 || encoding == BGR16 || encoding == RGB16 || encoding == BGRA16 || encoding == RGBA16 || encoding == BAYER_RGGB16 || encoding == BAYER_BGGR16 || encoding == BAYER_GBRG16 || encoding == BAYER_GRBG16) return 16; // Now all the generic content encodings // TODO: Rewrite with regex when ROS supports C++11 for (size_t i=0; i < sizeof(ABSTRACT_ENCODING_PREFIXES) / sizeof(*ABSTRACT_ENCODING_PREFIXES); i++) { std::string prefix = ABSTRACT_ENCODING_PREFIXES[i]; if (encoding.substr(0, prefix.size()) != prefix) continue; if (encoding.size() == prefix.size()) return atoi(prefix.c_str()); // ex. 8UC -> 8 int n_channel = atoi(encoding.substr(prefix.size(), encoding.size() - prefix.size()).c_str()); // ex. 8UC10 -> 10 if (n_channel != 0) return atoi(prefix.c_str()); // valid encoding string } if (encoding == YUV422) return 8; throw std::runtime_error("Unknown encoding " + encoding); return -1; } } } #endif ros-common-msgs-1.12.7/sensor_msgs/include/sensor_msgs/impl/000077500000000000000000000000001337176563300241505ustar00rootroot00000000000000ros-common-msgs-1.12.7/sensor_msgs/include/sensor_msgs/impl/point_cloud2_iterator.h000066400000000000000000000341761337176563300306460ustar00rootroot00000000000000/* * Software License Agreement (BSD License) * * Copyright (c) 2013, Open Source Robotics Foundation * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Open Source Robotics Foundation nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef SENSOR_MSGS_IMPL_POINT_CLOUD_ITERATOR_H #define SENSOR_MSGS_IMPL_POINT_CLOUD_ITERATOR_H #include #include #include #include #include /** * \brief Private implementation used by PointCloud2Iterator * \author Vincent Rabaud */ namespace { /** Return the size of a datatype (which is an enum of sensor_msgs::PointField::) in bytes * @param datatype one of the enums of sensor_msgs::PointField:: */ inline int sizeOfPointField(int datatype) { if ((datatype == sensor_msgs::PointField::INT8) || (datatype == sensor_msgs::PointField::UINT8)) return 1; else if ((datatype == sensor_msgs::PointField::INT16) || (datatype == sensor_msgs::PointField::UINT16)) return 2; else if ((datatype == sensor_msgs::PointField::INT32) || (datatype == sensor_msgs::PointField::UINT32) || (datatype == sensor_msgs::PointField::FLOAT32)) return 4; else if (datatype == sensor_msgs::PointField::FLOAT64) return 8; else { std::stringstream err; err << "PointField of type " << datatype << " does not exist"; throw std::runtime_error(err.str()); } return -1; } /** Private function that adds a PointField to the "fields" member of a PointCloud2 * @param cloud_msg the PointCloud2 to add a field to * @param name the name of the field * @param count the number of elements in the PointField * @param datatype the datatype of the elements * @param offset the offset of that element * @return the offset of the next PointField that will be added to the PointCLoud2 */ inline int addPointField(sensor_msgs::PointCloud2 &cloud_msg, const std::string &name, int count, int datatype, int offset) { sensor_msgs::PointField point_field; point_field.name = name; point_field.count = count; point_field.datatype = datatype; point_field.offset = offset; cloud_msg.fields.push_back(point_field); // Update the offset return offset + point_field.count * sizeOfPointField(datatype); } } //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// namespace sensor_msgs { inline PointCloud2Modifier::PointCloud2Modifier(PointCloud2& cloud_msg) : cloud_msg_(cloud_msg) { } inline size_t PointCloud2Modifier::size() const { return cloud_msg_.data.size() / cloud_msg_.point_step; } inline void PointCloud2Modifier::reserve(size_t size) { cloud_msg_.data.reserve(size * cloud_msg_.point_step); } inline void PointCloud2Modifier::resize(size_t size) { cloud_msg_.data.resize(size * cloud_msg_.point_step); // Update height/width if (cloud_msg_.height == 1) { cloud_msg_.width = size; cloud_msg_.row_step = size * cloud_msg_.point_step; } else if (cloud_msg_.width == 1) cloud_msg_.height = size; else { cloud_msg_.height = 1; cloud_msg_.width = size; cloud_msg_.row_step = size * cloud_msg_.point_step; } } inline void PointCloud2Modifier::clear() { cloud_msg_.data.clear(); // Update height/width if (cloud_msg_.height == 1) cloud_msg_.row_step = cloud_msg_.width = 0; else if (cloud_msg_.width == 1) cloud_msg_.height = 0; else cloud_msg_.row_step = cloud_msg_.width = cloud_msg_.height = 0; } /** * @brief Function setting some fields in a PointCloud and adjusting the * internals of the PointCloud2 * @param n_fields the number of fields to add. The fields are given as * triplets: name of the field as char*, number of elements in the * field, the datatype of the elements in the field * * E.g, you create your PointCloud2 message with XYZ/RGB as follows: *
 *   setPointCloud2FieldsByString(cloud_msg, 4, "x", 1, sensor_msgs::PointField::FLOAT32,
 *                                              "y", 1, sensor_msgs::PointField::FLOAT32,
 *                                              "z", 1, sensor_msgs::PointField::FLOAT32,
 *                                              "rgb", 1, sensor_msgs::PointField::FLOAT32);
 * 
* WARNING: THIS DOES NOT TAKE INTO ACCOUNT ANY PADDING AS DONE UNTIL HYDRO * For simple usual cases, the overloaded setPointCloud2FieldsByString is what you want. */ inline void PointCloud2Modifier::setPointCloud2Fields(int n_fields, ...) { cloud_msg_.fields.clear(); cloud_msg_.fields.reserve(n_fields); va_list vl; va_start(vl, n_fields); int offset = 0; for (int i = 0; i < n_fields; ++i) { // Create the corresponding PointField std::string name(va_arg(vl, char*)); int count(va_arg(vl, int)); int datatype(va_arg(vl, int)); offset = addPointField(cloud_msg_, name, count, datatype, offset); } va_end(vl); // Resize the point cloud accordingly cloud_msg_.point_step = offset; cloud_msg_.row_step = cloud_msg_.width * cloud_msg_.point_step; cloud_msg_.data.resize(cloud_msg_.height * cloud_msg_.row_step); } /** * @brief Function setting some fields in a PointCloud and adjusting the * internals of the PointCloud2 * @param n_fields the number of fields to add. The fields are given as * strings: "xyz" (3 floats), "rgb" (3 uchar stacked in a float), * "rgba" (4 uchar stacked in a float) * @return void * * WARNING: THIS FUNCTION DOES ADD ANY NECESSARY PADDING TRANSPARENTLY */ inline void PointCloud2Modifier::setPointCloud2FieldsByString(int n_fields, ...) { cloud_msg_.fields.clear(); cloud_msg_.fields.reserve(n_fields); va_list vl; va_start(vl, n_fields); int offset = 0; for (int i = 0; i < n_fields; ++i) { // Create the corresponding PointFields std::string field_name = std::string(va_arg(vl, char*)); if (field_name == "xyz") { sensor_msgs::PointField point_field; // Do x, y and z offset = addPointField(cloud_msg_, "x", 1, sensor_msgs::PointField::FLOAT32, offset); offset = addPointField(cloud_msg_, "y", 1, sensor_msgs::PointField::FLOAT32, offset); offset = addPointField(cloud_msg_, "z", 1, sensor_msgs::PointField::FLOAT32, offset); offset += sizeOfPointField(sensor_msgs::PointField::FLOAT32); } else if ((field_name == "rgb") || (field_name == "rgba")) { offset = addPointField(cloud_msg_, field_name, 1, sensor_msgs::PointField::FLOAT32, offset); offset += 3 * sizeOfPointField(sensor_msgs::PointField::FLOAT32); } else throw std::runtime_error("Field " + field_name + " does not exist"); } va_end(vl); // Resize the point cloud accordingly cloud_msg_.point_step = offset; cloud_msg_.row_step = cloud_msg_.width * cloud_msg_.point_step; cloud_msg_.data.resize(cloud_msg_.height * cloud_msg_.row_step); } //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// namespace impl { /** */ template class V> PointCloud2IteratorBase::PointCloud2IteratorBase() : data_char_(0), data_(0), data_end_(0) { } /** * @param cloud_msg_ The PointCloud2 to iterate upon * @param field_name The field to iterate upon */ template class V> PointCloud2IteratorBase::PointCloud2IteratorBase(C &cloud_msg, const std::string &field_name) { int offset = set_field(cloud_msg, field_name); data_char_ = &(cloud_msg.data.front()) + offset; data_ = reinterpret_cast(data_char_); data_end_ = reinterpret_cast(&(cloud_msg.data.back()) + 1 + offset); } /** Assignment operator * @param iter the iterator to copy data from * @return a reference to *this */ template class V> V& PointCloud2IteratorBase::operator =(const V &iter) { if (this != &iter) { point_step_ = iter.point_step_; data_char_ = iter.data_char_; data_ = iter.data_; data_end_ = iter.data_end_; is_bigendian_ = iter.is_bigendian_; } return *this; } /** Access the i th element starting at the current pointer (useful when a field has several elements of the same * type) * @param i * @return a reference to the i^th value from the current position */ template class V> TT& PointCloud2IteratorBase::operator [](size_t i) const { return *(data_ + i); } /** Dereference the iterator. Equivalent to accessing it through [0] * @return the value to which the iterator is pointing */ template class V> TT& PointCloud2IteratorBase::operator *() const { return *data_; } /** Increase the iterator to the next element * @return a reference to the updated iterator */ template class V> V& PointCloud2IteratorBase::operator ++() { data_char_ += point_step_; data_ = reinterpret_cast(data_char_); return *static_cast*>(this); } /** Basic pointer addition * @param i the amount to increase the iterator by * @return an iterator with an increased position */ template class V> V PointCloud2IteratorBase::operator +(int i) { V res = *static_cast*>(this); res.data_char_ += i*point_step_; res.data_ = reinterpret_cast(res.data_char_); return res; } /** Increase the iterator by a certain amount * @return a reference to the updated iterator */ template class V> V& PointCloud2IteratorBase::operator +=(int i) { data_char_ += i*point_step_; data_ = reinterpret_cast(data_char_); return *static_cast*>(this); } /** Compare to another iterator * @return whether the current iterator points to a different address than the other one */ template class V> bool PointCloud2IteratorBase::operator !=(const V& iter) const { return iter.data_ != data_; } /** Return the end iterator * @return the end iterator (useful when performing normal iterator processing with ++) */ template class V> V PointCloud2IteratorBase::end() const { V res = *static_cast*>(this); res.data_ = data_end_; return res; } /** Common code to set the field of the PointCloud2 * @param cloud_msg the PointCloud2 to modify * @param field_name the name of the field to iterate upon * @return the offset at which the field is found */ template class V> int PointCloud2IteratorBase::set_field(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) { is_bigendian_ = cloud_msg.is_bigendian; point_step_ = cloud_msg.point_step; // make sure the channel is valid std::vector::const_iterator field_iter = cloud_msg.fields.begin(), field_end = cloud_msg.fields.end(); while ((field_iter != field_end) && (field_iter->name != field_name)) ++field_iter; if (field_iter == field_end) { // Handle the special case of r,g,b,a (we assume they are understood as the channels of an rgb or rgba field) if ((field_name == "r") || (field_name == "g") || (field_name == "b") || (field_name == "a")) { // Check that rgb or rgba is present field_iter = cloud_msg.fields.begin(); while ((field_iter != field_end) && (field_iter->name != "rgb") && (field_iter->name != "rgba")) ++field_iter; if (field_iter == field_end) throw std::runtime_error("Field " + field_name + " does not exist"); if (field_name == "r") { if (is_bigendian_) return field_iter->offset + 1; else return field_iter->offset + 2; } if (field_name == "g") { if (is_bigendian_) return field_iter->offset + 2; else return field_iter->offset + 1; } if (field_name == "b") { if (is_bigendian_) return field_iter->offset + 3; else return field_iter->offset + 0; } if (field_name == "a") { if (is_bigendian_) return field_iter->offset + 0; else return field_iter->offset + 3; } } else throw std::runtime_error("Field " + field_name + " does not exist"); } return field_iter->offset; } } } #endif// SENSOR_MSGS_IMPL_POINT_CLOUD_ITERATOR_H ros-common-msgs-1.12.7/sensor_msgs/include/sensor_msgs/point_cloud2_iterator.h000066400000000000000000000276151337176563300277050ustar00rootroot00000000000000/* * Software License Agreement (BSD License) * * Copyright (c) 2013, Open Source Robotics Foundation * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Open Source Robotics Foundation nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #ifndef SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H #define SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H #include #include #include #include /** * \brief Tools for manipulating sensor_msgs * * This file provides two sets of utilities to modify and parse PointCloud2 * The first set allows you to conveniently set the fields by hand: *
 *   #include 
 *   // Create a PointCloud2
 *   sensor_msgs::PointCloud2 cloud_msg;
 *   // Fill some internals of the PoinCloud2 like the header/width/height ...
 *   cloud_msgs.height = 1;  cloud_msgs.width = 4;
 *   // Set the point fields to xyzrgb and resize the vector with the following command
 *   // 4 is for the number of added fields. Each come in triplet: the name of the PointField,
 *   // the number of occurrences of the type in the PointField, the type of the PointField
 *   sensor_msgs::PointCloud2Modifier modifier(cloud_msg);
 *   modifier.setPointCloud2Fields(4, "x", 1, sensor_msgs::PointField::FLOAT32,
 *                                            "y", 1, sensor_msgs::PointField::FLOAT32,
 *                                            "z", 1, sensor_msgs::PointField::FLOAT32,
 *                                            "rgb", 1, sensor_msgs::PointField::FLOAT32);
 *   // For convenience and the xyz, rgb, rgba fields, you can also use the following overloaded function.
 *   // You have to be aware that the following function does add extra padding for backward compatibility though
 *   // so it is definitely the solution of choice for PointXYZ and PointXYZRGB
 *   // 2 is for the number of fields to add
 *   modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
 *   // You can then reserve / resize as usual
 *   modifier.resize(100);
 * 
* * The second set allow you to traverse your PointCloud using an iterator: *
 *   // Define some raw data we'll put in the PointCloud2
 *   float point_data[] = {1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0, 11.0, 12.0};
 *   uint8_t color_data[] = {40, 80, 120, 160, 200, 240, 20, 40, 60, 80, 100, 120};
 *   // Define the iterators. When doing so, you define the Field you would like to iterate upon and
 *   // the type of you would like returned: it is not necessary the type of the PointField as sometimes
 *   // you pack data in another type (e.g. 3 uchar + 1 uchar for RGB are packed in a float)
 *   sensor_msgs::PointCloud2Iterator iter_x(cloud_msg, "x");
 *   sensor_msgs::PointCloud2Iterator iter_y(cloud_msg, "y");
 *   sensor_msgs::PointCloud2Iterator iter_z(cloud_msg, "z");
 *   // Even though the r,g,b,a fields do not exist (it's usually rgb, rgba), you can create iterators for
 *   // those: they will handle data packing for you (in little endian RGB is packed as *,R,G,B in a float
 *   // and RGBA as A,R,G,B)
 *   sensor_msgs::PointCloud2Iterator iter_r(cloud_msg, "r");
 *   sensor_msgs::PointCloud2Iterator iter_g(cloud_msg, "g");
 *   sensor_msgs::PointCloud2Iterator iter_b(cloud_msg, "b");
 *   // Fill the PointCloud2
 *   for(size_t i=0; i
 */

namespace sensor_msgs
{
/**
 * @brief Enables modifying a sensor_msgs::PointCloud2 like a container
 */
class PointCloud2Modifier
{
public:
  /**
   * @brief Default constructor
   * @param cloud_msg The sensor_msgs::PointCloud2 to modify
   */
  PointCloud2Modifier(PointCloud2& cloud_msg);

  /**
   * @return the number of T's in the original sensor_msgs::PointCloud2
   */
  size_t size() const;

  /**
   * @param size The number of T's to reserve in the original sensor_msgs::PointCloud2 for
   */
  void reserve(size_t size);

  /**
   * @param size The number of T's to change the size of the original sensor_msgs::PointCloud2 by
   */
  void resize(size_t size);

  /**
   * @brief remove all T's from the original sensor_msgs::PointCloud2
   */
  void clear();

  /**
   * @brief Function setting some fields in a PointCloud and adjusting the
   *        internals of the PointCloud2
   * @param n_fields the number of fields to add. The fields are given as
   *        triplets: name of the field as char*, number of elements in the
   *        field, the datatype of the elements in the field
   *
   * E.g, you create your PointCloud2 message with XYZ/RGB as follows:
   * 
   *   setPointCloud2Fields(cloud_msg, 4, "x", 1, sensor_msgs::PointField::FLOAT32,
   *                                              "y", 1, sensor_msgs::PointField::FLOAT32,
   *                                              "z", 1, sensor_msgs::PointField::FLOAT32,
   *                                              "rgb", 1, sensor_msgs::PointField::FLOAT32);
   * 
* WARNING: THIS DOES NOT TAKE INTO ACCOUNT ANY PADDING AS DONE UNTIL HYDRO * For simple usual cases, the overloaded setPointCloud2FieldsByString is what you want. */ void setPointCloud2Fields(int n_fields, ...); /** * @brief Function setting some fields in a PointCloud and adjusting the * internals of the PointCloud2 * @param n_fields the number of fields to add. The fields are given as * strings: "xyz" (3 floats), "rgb" (3 uchar stacked in a float), * "rgba" (4 uchar stacked in a float) * @return void * * WARNING: THIS FUNCTION DOES ADD ANY NECESSARY PADDING TRANSPARENTLY */ void setPointCloud2FieldsByString(int n_fields, ...); protected: /** A reference to the original sensor_msgs::PointCloud2 that we read */ PointCloud2& cloud_msg_; }; namespace impl { /** Private base class for PointCloud2Iterator and PointCloud2ConstIterator * T is the type of the value on which the child class will be templated * TT is the type of the value to be retrieved (same as T except for constness) * U is the type of the raw data in PointCloud2 (only uchar and const uchar are supported) * C is the type of the pointcloud to intialize from (const or not) * V is the derived class (yop, curiously recurring template pattern) */ template class V> class PointCloud2IteratorBase { public: /** */ PointCloud2IteratorBase(); /** * @param cloud_msg The PointCloud2 to iterate upon * @param field_name The field to iterate upon */ PointCloud2IteratorBase(C &cloud_msg, const std::string &field_name); /** Assignment operator * @param iter the iterator to copy data from * @return a reference to *this */ V& operator =(const V& iter); /** Access the i th element starting at the current pointer (useful when a field has several elements of the same * type) * @param i * @return a reference to the i^th value from the current position */ TT& operator [](size_t i) const; /** Dereference the iterator. Equivalent to accessing it through [0] * @return the value to which the iterator is pointing */ TT& operator *() const; /** Increase the iterator to the next element * @return a reference to the updated iterator */ V& operator ++(); /** Basic pointer addition * @param i the amount to increase the iterator by * @return an iterator with an increased position */ V operator +(int i); /** Increase the iterator by a certain amount * @return a reference to the updated iterator */ V& operator +=(int i); /** Compare to another iterator * @return whether the current iterator points to a different address than the other one */ bool operator !=(const V& iter) const; /** Return the end iterator * @return the end iterator (useful when performing normal iterator processing with ++) */ V end() const; private: /** Common code to set the field of the PointCloud2 * @param cloud_msg the PointCloud2 to modify * @param field_name the name of the field to iterate upon * @return the offset at which the field is found */ int set_field(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name); /** The "point_step" of the original cloud */ int point_step_; /** The raw data in uchar* where the iterator is */ U* data_char_; /** The cast data where the iterator is */ TT* data_; /** The end() pointer of the iterator */ TT* data_end_; /** Whether the fields are stored as bigendian */ bool is_bigendian_; }; } /** * \brief Class that can iterate over a PointCloud2 * * T type of the element being iterated upon * E.g, you create your PointClou2 message as follows: *
 *   setPointCloud2FieldsByString(cloud_msg, 2, "xyz", "rgb");
 * 
* * For iterating over XYZ, you do : *
 *   sensor_msgs::PointCloud2Iterator iter_x(cloud_msg, "x");
 * 
* and then access X through iter_x[0] or *iter_x * You could create an iterator for Y and Z too but as they are consecutive, * you can just use iter_x[1] and iter_x[2] * * For iterating over RGB, you do: *
 * sensor_msgs::PointCloud2Iterator iter_rgb(cloud_msg, "rgb");
 * 
* and then access R,G,B through iter_rgb[0], iter_rgb[1], iter_rgb[2] */ template class PointCloud2Iterator : public impl::PointCloud2IteratorBase { public: PointCloud2Iterator(sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) : impl::PointCloud2IteratorBase::PointCloud2IteratorBase(cloud_msg, field_name) {} }; /** * \brief Same as a PointCloud2Iterator but for const data */ template class PointCloud2ConstIterator : public impl::PointCloud2IteratorBase { public: PointCloud2ConstIterator(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) : impl::PointCloud2IteratorBase::PointCloud2IteratorBase(cloud_msg, field_name) {} }; } #include #endif// SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H ros-common-msgs-1.12.7/sensor_msgs/include/sensor_msgs/point_cloud_conversion.h000066400000000000000000000166041337176563300301530ustar00rootroot00000000000000/* * Software License Agreement (BSD License) * * Copyright (c) 2010, Willow Garage, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * * $Id$ * */ #ifndef SENSOR_MSGS_POINT_CLOUD_CONVERSION_H #define SENSOR_MSGS_POINT_CLOUD_CONVERSION_H #include #include #include /** * \brief Convert between the old (sensor_msgs::PointCloud) and the new (sensor_msgs::PointCloud2) format. * \author Radu Bogdan Rusu */ namespace sensor_msgs { ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Get the index of a specified field (i.e., dimension/channel) * \param points the the point cloud message * \param field_name the string defining the field name */ static inline int getPointCloud2FieldIndex (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name) { // Get the index we need for (size_t d = 0; d < cloud.fields.size (); ++d) if (cloud.fields[d].name == field_name) return (d); return (-1); } //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Convert a sensor_msgs::PointCloud message to a sensor_msgs::PointCloud2 message. * \param input the message in the sensor_msgs::PointCloud format * \param output the resultant message in the sensor_msgs::PointCloud2 format */ static inline bool convertPointCloudToPointCloud2 (const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output) { output.header = input.header; output.width = input.points.size (); output.height = 1; output.fields.resize (3 + input.channels.size ()); // Convert x/y/z to fields output.fields[0].name = "x"; output.fields[1].name = "y"; output.fields[2].name = "z"; int offset = 0; // All offsets are *4, as all field data types are float32 for (size_t d = 0; d < output.fields.size (); ++d, offset += 4) { output.fields[d].offset = offset; output.fields[d].datatype = sensor_msgs::PointField::FLOAT32; output.fields[d].count = 1; } output.point_step = offset; output.row_step = output.point_step * output.width; // Convert the remaining of the channels to fields for (size_t d = 0; d < input.channels.size (); ++d) output.fields[3 + d].name = input.channels[d].name; output.data.resize (input.points.size () * output.point_step); output.is_bigendian = false; // @todo ? output.is_dense = false; // Copy the data points for (size_t cp = 0; cp < input.points.size (); ++cp) { memcpy (&output.data[cp * output.point_step + output.fields[0].offset], &input.points[cp].x, sizeof (float)); memcpy (&output.data[cp * output.point_step + output.fields[1].offset], &input.points[cp].y, sizeof (float)); memcpy (&output.data[cp * output.point_step + output.fields[2].offset], &input.points[cp].z, sizeof (float)); for (size_t d = 0; d < input.channels.size (); ++d) { if (input.channels[d].values.size() == input.points.size()) { memcpy (&output.data[cp * output.point_step + output.fields[3 + d].offset], &input.channels[d].values[cp], sizeof (float)); } } } return (true); } //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /** \brief Convert a sensor_msgs::PointCloud2 message to a sensor_msgs::PointCloud message. * \param input the message in the sensor_msgs::PointCloud2 format * \param output the resultant message in the sensor_msgs::PointCloud format */ static inline bool convertPointCloud2ToPointCloud (const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud &output) { output.header = input.header; output.points.resize (input.width * input.height); output.channels.resize (input.fields.size () - 3); // Get the x/y/z field offsets int x_idx = getPointCloud2FieldIndex (input, "x"); int y_idx = getPointCloud2FieldIndex (input, "y"); int z_idx = getPointCloud2FieldIndex (input, "z"); if (x_idx == -1 || y_idx == -1 || z_idx == -1) { std::cerr << "x/y/z coordinates not found! Cannot convert to sensor_msgs::PointCloud!" << std::endl; return (false); } int x_offset = input.fields[x_idx].offset; int y_offset = input.fields[y_idx].offset; int z_offset = input.fields[z_idx].offset; uint8_t x_datatype = input.fields[x_idx].datatype; uint8_t y_datatype = input.fields[y_idx].datatype; uint8_t z_datatype = input.fields[z_idx].datatype; // Convert the fields to channels int cur_c = 0; for (size_t d = 0; d < input.fields.size (); ++d) { if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset) continue; output.channels[cur_c].name = input.fields[d].name; output.channels[cur_c].values.resize (output.points.size ()); cur_c++; } // Copy the data points for (size_t cp = 0; cp < output.points.size (); ++cp) { // Copy x/y/z output.points[cp].x = sensor_msgs::readPointCloud2BufferValue(&input.data[cp * input.point_step + x_offset], x_datatype); output.points[cp].y = sensor_msgs::readPointCloud2BufferValue(&input.data[cp * input.point_step + y_offset], y_datatype); output.points[cp].z = sensor_msgs::readPointCloud2BufferValue(&input.data[cp * input.point_step + z_offset], z_datatype); // Copy the rest of the data int cur_c = 0; for (size_t d = 0; d < input.fields.size (); ++d) { if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset) continue; output.channels[cur_c++].values[cp] = sensor_msgs::readPointCloud2BufferValue(&input.data[cp * input.point_step + input.fields[d].offset], input.fields[d].datatype); } } return (true); } } #endif// SENSOR_MSGS_POINT_CLOUD_CONVERSION_H ros-common-msgs-1.12.7/sensor_msgs/include/sensor_msgs/point_field_conversion.h000066400000000000000000000215561337176563300301320ustar00rootroot00000000000000/* * Software License Agreement (BSD License) * * Robot Operating System code by the University of Osnabrück * Copyright (c) 2015, University of Osnabrück * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * 1. Redistributions of source code must retain the above * copyright notice, this list of conditions and the following * disclaimer. * * 2. Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * 3. Neither the name of the copyright holder nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * * * * point_field_conversion.h * * Created on: 16.07.2015 * Authors: Sebastian Pütz */ #ifndef SENSOR_MSGS_POINT_FIELD_CONVERSION_H #define SENSOR_MSGS_POINT_FIELD_CONVERSION_H /** * \brief This file provides a type to enum mapping for the different * PointField types and methods to read and write in * a PointCloud2 buffer for the different PointField types. * \author Sebastian Pütz */ namespace sensor_msgs{ /*! * \Enum to type mapping. */ template struct pointFieldTypeAsType {}; template<> struct pointFieldTypeAsType { typedef int8_t type; }; template<> struct pointFieldTypeAsType { typedef uint8_t type; }; template<> struct pointFieldTypeAsType { typedef int16_t type; }; template<> struct pointFieldTypeAsType { typedef uint16_t type; }; template<> struct pointFieldTypeAsType { typedef int32_t type; }; template<> struct pointFieldTypeAsType { typedef uint32_t type; }; template<> struct pointFieldTypeAsType { typedef float type; }; template<> struct pointFieldTypeAsType { typedef double type; }; /*! * \Type to enum mapping. */ template struct typeAsPointFieldType {}; template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::INT8; }; template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::UINT8; }; template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::INT16; }; template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::UINT16; }; template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::INT32; }; template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::UINT32; }; template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::FLOAT32; }; template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::FLOAT64; }; /*! * \Converts a value at the given pointer position, interpreted as the datatype * specified by the given template argument point_field_type, to the given * template type T and returns it. * \param data_ptr pointer into the point cloud 2 buffer * \tparam point_field_type sensor_msgs::PointField datatype value * \tparam T return type */ template inline T readPointCloud2BufferValue(const unsigned char* data_ptr){ typedef typename pointFieldTypeAsType::type type; return static_cast(*(reinterpret_cast(data_ptr))); } /*! * \Converts a value at the given pointer position interpreted as the datatype * specified by the given datatype parameter to the given template type and returns it. * \param data_ptr pointer into the point cloud 2 buffer * \param datatype sensor_msgs::PointField datatype value * \tparam T return type */ template inline T readPointCloud2BufferValue(const unsigned char* data_ptr, const unsigned char datatype){ switch(datatype){ case sensor_msgs::PointField::INT8: return readPointCloud2BufferValue(data_ptr); case sensor_msgs::PointField::UINT8: return readPointCloud2BufferValue(data_ptr); case sensor_msgs::PointField::INT16: return readPointCloud2BufferValue(data_ptr); case sensor_msgs::PointField::UINT16: return readPointCloud2BufferValue(data_ptr); case sensor_msgs::PointField::INT32: return readPointCloud2BufferValue(data_ptr); case sensor_msgs::PointField::UINT32: return readPointCloud2BufferValue(data_ptr); case sensor_msgs::PointField::FLOAT32: return readPointCloud2BufferValue(data_ptr); case sensor_msgs::PointField::FLOAT64: return readPointCloud2BufferValue(data_ptr); } // This should never be reached, but return statement added to avoid compiler warning. (#84) return T(); } /*! * \Inserts a given value at the given point position interpreted as the datatype * specified by the template argument point_field_type. * \param data_ptr pointer into the point cloud 2 buffer * \param value the value to insert * \tparam point_field_type sensor_msgs::PointField datatype value * \tparam T type of the value to insert */ template inline void writePointCloud2BufferValue(unsigned char* data_ptr, T value){ typedef typename pointFieldTypeAsType::type type; *(reinterpret_cast(data_ptr)) = static_cast(value); } /*! * \Inserts a given value at the given point position interpreted as the datatype * specified by the given datatype parameter. * \param data_ptr pointer into the point cloud 2 buffer * \param datatype sensor_msgs::PointField datatype value * \param value the value to insert * \tparam T type of the value to insert */ template inline void writePointCloud2BufferValue(unsigned char* data_ptr, const unsigned char datatype, T value){ switch(datatype){ case sensor_msgs::PointField::INT8: writePointCloud2BufferValue(data_ptr, value); break; case sensor_msgs::PointField::UINT8: writePointCloud2BufferValue(data_ptr, value); break; case sensor_msgs::PointField::INT16: writePointCloud2BufferValue(data_ptr, value); break; case sensor_msgs::PointField::UINT16: writePointCloud2BufferValue(data_ptr, value); break; case sensor_msgs::PointField::INT32: writePointCloud2BufferValue(data_ptr, value); break; case sensor_msgs::PointField::UINT32: writePointCloud2BufferValue(data_ptr, value); break; case sensor_msgs::PointField::FLOAT32: writePointCloud2BufferValue(data_ptr, value); break; case sensor_msgs::PointField::FLOAT64: writePointCloud2BufferValue(data_ptr, value); break; } } } #endif /* point_field_conversion.h */ ros-common-msgs-1.12.7/sensor_msgs/mainpage.dox000066400000000000000000000003261337176563300215200ustar00rootroot00000000000000/** \mainpage \htmlinclude manifest.html \b sensor_msgs is a package which collects the common message data types for robot sensors. It also provides a set of methods for conversion between these data types. */ ros-common-msgs-1.12.7/sensor_msgs/migration_rules/000077500000000000000000000000001337176563300224255ustar00rootroot00000000000000ros-common-msgs-1.12.7/sensor_msgs/migration_rules/sensor_msgs.bmr000066400000000000000000001720601337176563300254770ustar00rootroot00000000000000class update_robot_msgs_PointCloud_c47b5cedd2b77d241b27547ed7624840(MessageUpdateRule): old_type = "robot_msgs/PointCloud" old_full_text = """ Header header Point32[] pts ChannelFloat32[] chan ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id ================================================================================ MSG: robot_msgs/Point32 float32 x float32 y float32 z ================================================================================ MSG: robot_msgs/ChannelFloat32 string name float32[] vals """ new_type = "sensor_msgs/PointCloud" new_full_text = """ Header header geometry_msgs/Point32[] points ChannelFloat32[] channels ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id ================================================================================ MSG: geometry_msgs/Point32 float32 x float32 y float32 z ================================================================================ MSG: sensor_msgs/ChannelFloat32 string name float32[] values """ order = 0 migrated_types = [ ("Header","Header"), ("Point32","geometry_msgs/Point32"), ("ChannelFloat32","ChannelFloat32")] valid = True def update(self, old_msg, new_msg): self.migrate(old_msg.header, new_msg.header) self.migrate_array(old_msg.pts, new_msg.points, "geometry_msgs/Point32") self.migrate_array(old_msg.chan, new_msg.channels, "ChannelFloat32") class update_robot_msgs_ChannelFloat32_61c47e4621e471c885edb248b5dcafd5(MessageUpdateRule): old_type = "robot_msgs/ChannelFloat32" old_full_text = """ string name float32[] vals """ new_type = "sensor_msgs/ChannelFloat32" new_full_text = """ string name float32[] values """ order = 0 migrated_types = [] valid = True def update(self, old_msg, new_msg): new_msg.name = old_msg.name new_msg.values = old_msg.vals class update_image_msgs_CamInfo_a48ffa77e74ab6901331e50745dff353(MessageUpdateRule): old_type = "image_msgs/CamInfo" old_full_text = """ # This message defines meta information for a camera. It should be in a # camera namespace and accompanied by up to 5 image topics named: # # image_raw, image, image_color, image_rect, and image_rect_color Header header uint32 height uint32 width float64[5] D # Distortion: k1, k2, t1, t2, k3 float64[9] K # original camera matrix float64[9] R # rectification matrix float64[12] P # projection/camera matrix # Should put exposure, gain, etc. information here as well ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id """ new_type = "sensor_msgs/CameraInfo" new_full_text = """ # This message defines meta information for a camera. It should be in a # camera namespace and accompanied by up to 5 image topics named: # # image_raw, image, image_color, image_rect, and image_rect_color # # The meaning of the camera parameters are described in detail at # http://pr.willowgarage.com/wiki/Camera_Calibration. Header header # Resolution in pixels uint32 height uint32 width ######################## # Intrinsic parameters # ######################## # Distortion parameters: k1, k2, t1, t2, k3 # These model radial and tangential distortion of the camera. float64[5] D # 5x1 vector # Original camera matrix # Projects 3D points in the camera coordinate frame to 2D pixel # coordinates using the focal lengths (fx, fy) and principal point # (cx, cy): # [fx 0 cx] # K = [ 0 fy cy] # [ 0 0 1] float64[9] K # 3x3 row-major matrix ######################## # Extrinsic parameters # ######################## # Rectification matrix (stereo cameras only) # A homography which takes an image to the ideal stereo image plane # so that epipolar lines in both stereo images are parallel. float64[9] R # 3x3 row-major matrix # Projection/camera matrix # Projects 3D points in a world coordinate frame to 2D pixel coordinates. float64[12] P # 3x4 row-major matrix ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id """ order = 0 migrated_types = [ ("Header","Header"),] valid = True def update(self, old_msg, new_msg): self.migrate(old_msg.header, new_msg.header) new_msg.height = old_msg.height new_msg.width = old_msg.width new_msg.D = old_msg.D new_msg.K = old_msg.K new_msg.R = old_msg.R new_msg.P = old_msg.P class update_sensor_msgs_CameraInfo_a48ffa77e74ab6901331e50745dff353(MessageUpdateRule): old_type = "sensor_msgs/CameraInfo" old_full_text = """ # This message defines meta information for a camera. It should be in a # camera namespace and accompanied by up to 5 image topics named: # # image_raw, image, image_color, image_rect, and image_rect_color # # The meaning of the camera parameters are described in detail at # http://pr.willowgarage.com/wiki/Camera_Calibration. Header header # Resolution in pixels uint32 height uint32 width ######################## # Intrinsic parameters # ######################## # Distortion parameters: k1, k2, t1, t2, k3 # These model radial and tangential distortion of the camera. float64[5] D # 5x1 vector # Original camera matrix # Projects 3D points in the camera coordinate frame to 2D pixel # coordinates using the focal lengths (fx, fy) and principal point # (cx, cy): # [fx 0 cx] # K = [ 0 fy cy] # [ 0 0 1] float64[9] K # 3x3 row-major matrix ######################## # Extrinsic parameters # ######################## # Rectification matrix (stereo cameras only) # A homography which takes an image to the ideal stereo image plane # so that epipolar lines in both stereo images are parallel. float64[9] R # 3x3 row-major matrix # Projection/camera matrix # Projects 3D points in a world coordinate frame to 2D pixel coordinates. float64[12] P # 3x4 row-major matrix ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id """ new_type = "sensor_msgs/CameraInfo" new_full_text = """ # This message defines meta information for a camera. It should be in a # camera namespace and accompanied by up to 5 image topics named: # # image_raw, image, image_color, image_rect, and image_rect_color # # The meaning of the camera parameters are described in detail at # http://pr.willowgarage.com/wiki/Camera_Calibration. ########################## # Image acquisition info # ########################## # Time of image acquisition, camera coordinate frame ID Header header # Camera resolution in pixels uint32 height uint32 width # Region of interest (subwindow of full camera resolution), if applicable RegionOfInterest roi ######################## # Intrinsic parameters # ######################## # Distortion parameters: k1, k2, t1, t2, k3 # These model radial and tangential distortion of the camera. float64[5] D # 5x1 vector # Original camera matrix # Projects 3D points in the camera coordinate frame to 2D pixel # coordinates using the focal lengths (fx, fy) and principal point # (cx, cy): # [fx 0 cx] # K = [ 0 fy cy] # [ 0 0 1] float64[9] K # 3x3 row-major matrix ######################## # Extrinsic parameters # ######################## # Rectification matrix (stereo cameras only) # A homography which takes an image to the ideal stereo image plane # so that epipolar lines in both stereo images are parallel. float64[9] R # 3x3 row-major matrix # Projection/camera matrix # Projects 3D points in a world coordinate frame to 2D pixel coordinates. float64[12] P # 3x4 row-major matrix ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id ================================================================================ MSG: sensor_msgs/RegionOfInterest uint32 x_offset uint32 y_offset uint32 height uint32 width """ order = 0 migrated_types = [ ("Header","Header"),] valid = True def update(self, old_msg, new_msg): self.migrate(old_msg.header, new_msg.header) new_msg.height = old_msg.height new_msg.width = old_msg.width new_msg.roi = self.get_new_class('sensor_msgs/RegionOfInterest')(0,0,old_msg.height,old_msg.width) new_msg.D = old_msg.D new_msg.K = old_msg.K new_msg.R = old_msg.R new_msg.P = old_msg.P class update_sensor_msgs_Image_97d4ca3868dc81af4a2403bcb6558cb0(MessageUpdateRule): old_type = "sensor_msgs/Image" old_full_text = """ Header header # Header string label # Label for the image string encoding # Specifies the color encoding of the data # Acceptable values are: # 1 channel types: # mono, bayer_rggb, bayer_gbrg, bayer_grbg, bayer_bggr # 3 channel types: # rgb, bgr # 4 channel types: # rgba, bgra, yuv422 # 6 channel types: # yuv411 # N channel types: # other string depth # Specifies the depth of the data: # Acceptable values: # uint8, int8, uint16, int16, uint32, int32, uint64, int64, float32, float64 # Based on depth ONE of the following MultiArrays may contain data. # The multi-array MUST have 3 dimensions, labeled as "height", # "width", and "channel", though depending on usage the ordering of # the dimensions may very. Note that IPL Image convention will order # these as: height, width, channel, which is the preferred ordering # unless performance dictates otherwise. # # Height, width, and number of channels are specified in the dimension # sizes within the appropriate MultiArray std_msgs/UInt8MultiArray uint8_data std_msgs/Int8MultiArray int8_data std_msgs/UInt16MultiArray uint16_data std_msgs/Int16MultiArray int16_data std_msgs/UInt32MultiArray uint32_data std_msgs/Int32MultiArray int32_data std_msgs/UInt64MultiArray uint64_data std_msgs/Int64MultiArray int64_data std_msgs/Float32MultiArray float32_data std_msgs/Float64MultiArray float64_data ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id ================================================================================ MSG: std_msgs/UInt8MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout uint8[] data # array of data ================================================================================ MSG: std_msgs/MultiArrayLayout # The multiarray declares a generic multi-dimensional array of a # particular data type. Dimensions are ordered from outer most # to inner most. MultiArrayDimension[] dim # Array of dimension properties uint32 data_offset # padding bytes at front of data # Accessors should ALWAYS be written in terms of dimension stride # and specified outer-most dimension first. # # multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] # # A standard, 3-channel 640x480 image with interleaved color channels # would be specified as: # # dim[0].label = "height" # dim[0].size = 480 # dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) # dim[1].label = "width" # dim[1].size = 640 # dim[1].stride = 3*640 = 1920 # dim[2].label = "channel" # dim[2].size = 3 # dim[2].stride = 3 # # multiarray(i,j,k) refers to the ith row, jth column, and kth channel. ================================================================================ MSG: std_msgs/MultiArrayDimension string label # label of given dimension uint32 size # size of given dimension (in type units) uint32 stride # stride of given dimension ================================================================================ MSG: std_msgs/Int8MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout int8[] data # array of data ================================================================================ MSG: std_msgs/UInt16MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout uint16[] data # array of data ================================================================================ MSG: std_msgs/Int16MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout int16[] data # array of data ================================================================================ MSG: std_msgs/UInt32MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout uint32[] data # array of data ================================================================================ MSG: std_msgs/Int32MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout int32[] data # array of data ================================================================================ MSG: std_msgs/UInt64MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout uint64[] data # array of data ================================================================================ MSG: std_msgs/Int64MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout int64[] data # array of data ================================================================================ MSG: std_msgs/Float32MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout float32[] data # array of data ================================================================================ MSG: std_msgs/Float64MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout float64[] data # array of data """ new_type = "sensor_msgs/Image" new_full_text = """ Header header # Header uint32 height # image height, that is, number of rows uint32 width # image width, that is, number of columns # The legal values for encoding are in file src/image_encodings.cpp # If you want to standardize a new string format, join ros-users@lists.sourceforge.net and send an email proposing a new encoding. string encoding # Encoding of pixels -- channel meaning, ordering, size -- taken from the list of strings in src/image_encodings.cpp uint8 is_bigendian # is this data bigendian uint32 step # Full row length in bytes uint8[] data # actual matrix data, size is (step * rows) ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id """ order = 0 migrated_types = [ ("Header","Header"),] valid = True def update_empty(self, old_msg, new_msg): pass def update_mono_uint8(self, old_msg, new_msg): assert (len(old_msg.uint8_data.layout.dim) == 3 and old_msg.uint8_data.layout.dim[0].label == 'height' and old_msg.uint8_data.layout.dim[1].label == 'width' and old_msg.uint8_data.layout.dim[2].label == 'channel'), \ 'This rule only supports migration images with 3 dimensions ordered: height, width, channel' self.migrate(old_msg.header, new_msg.header) new_msg.encoding = 'mono8' new_msg.step = old_msg.uint8_data.layout.dim[1].stride new_msg.data = old_msg.uint8_data.data new_msg.height = old_msg.uint8_data.layout.dim[0].size new_msg.width = old_msg.uint8_data.layout.dim[1].size new_msg.is_bigendian = 0 def update_rgb_uint8(self, old_msg, new_msg): assert (len(old_msg.uint8_data.layout.dim) == 3 and old_msg.uint8_data.layout.dim[0].label == 'height' and old_msg.uint8_data.layout.dim[1].label == 'width' and old_msg.uint8_data.layout.dim[2].label == 'channel'), \ 'This rule only supports migration images with 3 dimensions ordered: height, width, channel' self.migrate(old_msg.header, new_msg.header) new_msg.encoding = 'rgb8' new_msg.step = old_msg.uint8_data.layout.dim[1].stride new_msg.data = old_msg.uint8_data.data new_msg.height = old_msg.uint8_data.layout.dim[0].size new_msg.width = old_msg.uint8_data.layout.dim[1].size new_msg.is_bigendian = 0 def update_bgr_uint8(self, old_msg, new_msg): assert (len(old_msg.uint8_data.layout.dim) == 3 and old_msg.uint8_data.layout.dim[0].label == 'height' and old_msg.uint8_data.layout.dim[1].label == 'width' and old_msg.uint8_data.layout.dim[2].label == 'channel'), \ 'This rule only supports migration images with 3 dimensions ordered: height, width, channel' self.migrate(old_msg.header, new_msg.header) new_msg.encoding = 'bgr8' new_msg.step = old_msg.uint8_data.layout.dim[1].stride new_msg.data = old_msg.uint8_data.data new_msg.height = old_msg.uint8_data.layout.dim[0].size new_msg.width = old_msg.uint8_data.layout.dim[1].size new_msg.is_bigendian = 0 def update(self, old_msg, new_msg): encoding_map = {('',''): self.update_empty, ('other','none'): self.update_empty, ('mono', 'uint8'): self.update_mono_uint8, ('rgb', 'uint8'): self.update_rgb_uint8, ('bgr', 'uint8'): self.update_bgr_uint8} key = (old_msg.encoding, old_msg.depth) assert key in encoding_map, 'This rule does not support migrating from %s %s'%key encoding_map[key](old_msg, new_msg) class update_image_msgs_Image_97d4ca3868dc81af4a2403bcb6558cb0(MessageUpdateRule): old_type = "image_msgs/Image" old_full_text = """ Header header # Header string label # Label for the image string encoding # Specifies the color encoding of the data # Acceptable values are: # 1 channel types: # mono, bayer_rggb, bayer_gbrg, bayer_grbg, bayer_bggr # 3 channel types: # rgb, bgr # 4 channel types: # rgba, bgra, yuv422 # 6 channel types: # yuv411 # N channel types: # other string depth # Specifies the depth of the data: # Acceptable values: # uint8, int8, uint16, int16, uint32, int32, uint64, int64, float32, float64 # Based on depth ONE of the following MultiArrays may contain data. # The multi-array MUST have 3 dimensions, labeled as "height", # "width", and "channel", though depending on usage the ordering of # the dimensions may very. Note that IPL Image convention will order # these as: height, width, channel, which is the preferred ordering # unless performance dictates otherwise. # # Height, width, and number of channels are specified in the dimension # sizes within the appropriate MultiArray std_msgs/UInt8MultiArray uint8_data std_msgs/Int8MultiArray int8_data std_msgs/UInt16MultiArray uint16_data std_msgs/Int16MultiArray int16_data std_msgs/UInt32MultiArray uint32_data std_msgs/Int32MultiArray int32_data std_msgs/UInt64MultiArray uint64_data std_msgs/Int64MultiArray int64_data std_msgs/Float32MultiArray float32_data std_msgs/Float64MultiArray float64_data ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id ================================================================================ MSG: std_msgs/UInt8MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout uint8[] data # array of data ================================================================================ MSG: std_msgs/MultiArrayLayout # The multiarray declares a generic multi-dimensional array of a # particular data type. Dimensions are ordered from outer most # to inner most. MultiArrayDimension[] dim # Array of dimension properties uint32 data_offset # padding bytes at front of data # Accessors should ALWAYS be written in terms of dimension stride # and specified outer-most dimension first. # # multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] # # A standard, 3-channel 640x480 image with interleaved color channels # would be specified as: # # dim[0].label = "height" # dim[0].size = 480 # dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) # dim[1].label = "width" # dim[1].size = 640 # dim[1].stride = 3*640 = 1920 # dim[2].label = "channel" # dim[2].size = 3 # dim[2].stride = 3 # # multiarray(i,j,k) refers to the ith row, jth column, and kth channel. ================================================================================ MSG: std_msgs/MultiArrayDimension string label # label of given dimension uint32 size # size of given dimension (in type units) uint32 stride # stride of given dimension ================================================================================ MSG: std_msgs/Int8MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout int8[] data # array of data ================================================================================ MSG: std_msgs/UInt16MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout uint16[] data # array of data ================================================================================ MSG: std_msgs/Int16MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout int16[] data # array of data ================================================================================ MSG: std_msgs/UInt32MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout uint32[] data # array of data ================================================================================ MSG: std_msgs/Int32MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout int32[] data # array of data ================================================================================ MSG: std_msgs/UInt64MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout uint64[] data # array of data ================================================================================ MSG: std_msgs/Int64MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout int64[] data # array of data ================================================================================ MSG: std_msgs/Float32MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout float32[] data # array of data ================================================================================ MSG: std_msgs/Float64MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout float64[] data # array of data """ new_type = "sensor_msgs/Image" new_full_text = """ Header header # Header string label # Label for the image string encoding # Specifies the color encoding of the data # Acceptable values are: # 1 channel types: # mono, bayer_rggb, bayer_gbrg, bayer_grbg, bayer_bggr # 3 channel types: # rgb, bgr # 4 channel types: # rgba, bgra, yuv422 # 6 channel types: # yuv411 # N channel types: # other string depth # Specifies the depth of the data: # Acceptable values: # uint8, int8, uint16, int16, uint32, int32, uint64, int64, float32, float64 # Based on depth ONE of the following MultiArrays may contain data. # The multi-array MUST have 3 dimensions, labeled as "height", # "width", and "channel", though depending on usage the ordering of # the dimensions may very. Note that IPL Image convention will order # these as: height, width, channel, which is the preferred ordering # unless performance dictates otherwise. # # Height, width, and number of channels are specified in the dimension # sizes within the appropriate MultiArray std_msgs/UInt8MultiArray uint8_data std_msgs/Int8MultiArray int8_data std_msgs/UInt16MultiArray uint16_data std_msgs/Int16MultiArray int16_data std_msgs/UInt32MultiArray uint32_data std_msgs/Int32MultiArray int32_data std_msgs/UInt64MultiArray uint64_data std_msgs/Int64MultiArray int64_data std_msgs/Float32MultiArray float32_data std_msgs/Float64MultiArray float64_data ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id ================================================================================ MSG: std_msgs/UInt8MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout uint8[] data # array of data ================================================================================ MSG: std_msgs/MultiArrayLayout # The multiarray declares a generic multi-dimensional array of a # particular data type. Dimensions are ordered from outer most # to inner most. MultiArrayDimension[] dim # Array of dimension properties uint32 data_offset # padding bytes at front of data # Accessors should ALWAYS be written in terms of dimension stride # and specified outer-most dimension first. # # multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] # # A standard, 3-channel 640x480 image with interleaved color channels # would be specified as: # # dim[0].label = "height" # dim[0].size = 480 # dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) # dim[1].label = "width" # dim[1].size = 640 # dim[1].stride = 3*640 = 1920 # dim[2].label = "channel" # dim[2].size = 3 # dim[2].stride = 3 # # multiarray(i,j,k) refers to the ith row, jth column, and kth channel. ================================================================================ MSG: std_msgs/MultiArrayDimension string label # label of given dimension uint32 size # size of given dimension (in type units) uint32 stride # stride of given dimension ================================================================================ MSG: std_msgs/Int8MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout int8[] data # array of data ================================================================================ MSG: std_msgs/UInt16MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout uint16[] data # array of data ================================================================================ MSG: std_msgs/Int16MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout int16[] data # array of data ================================================================================ MSG: std_msgs/UInt32MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout uint32[] data # array of data ================================================================================ MSG: std_msgs/Int32MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout int32[] data # array of data ================================================================================ MSG: std_msgs/UInt64MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout uint64[] data # array of data ================================================================================ MSG: std_msgs/Int64MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout int64[] data # array of data ================================================================================ MSG: std_msgs/Float32MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout float32[] data # array of data ================================================================================ MSG: std_msgs/Float64MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout float64[] data # array of data """ order = 0 migrated_types = [ ("Header","Header"), ("Image","Image")] valid = True def update(self, old_msg, new_msg): self.migrate(old_msg, new_msg) class update_sensor_msgs_CompressedImage_9f25a34569b1b807704b985d4396ad35(MessageUpdateRule): old_type = "sensor_msgs/CompressedImage" old_full_text = """ Header header # Header string label # Label for the image string encoding # Specifies the color encoding of the data # Acceptable values are: # 1 channel types: # mono # 3 channel types: # rgb, bgr string format # Specifies the format of the data # Acceptable values: # jpeg std_msgs/UInt8MultiArray uint8_data ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id ================================================================================ MSG: std_msgs/UInt8MultiArray # Please look at the MultiArrayLayout message definition for # documentation on all multiarrays. MultiArrayLayout layout # specification of data layout uint8[] data # array of data ================================================================================ MSG: std_msgs/MultiArrayLayout # The multiarray declares a generic multi-dimensional array of a # particular data type. Dimensions are ordered from outer most # to inner most. MultiArrayDimension[] dim # Array of dimension properties uint32 data_offset # padding bytes at front of data # Accessors should ALWAYS be written in terms of dimension stride # and specified outer-most dimension first. # # multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k] # # A standard, 3-channel 640x480 image with interleaved color channels # would be specified as: # # dim[0].label = "height" # dim[0].size = 480 # dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image) # dim[1].label = "width" # dim[1].size = 640 # dim[1].stride = 3*640 = 1920 # dim[2].label = "channel" # dim[2].size = 3 # dim[2].stride = 3 # # multiarray(i,j,k) refers to the ith row, jth column, and kth channel. ================================================================================ MSG: std_msgs/MultiArrayDimension string label # label of given dimension uint32 size # size of given dimension (in type units) uint32 stride # stride of given dimension """ new_type = "sensor_msgs/CompressedImage" new_full_text = """ Header header # Header string format # Specifies the format of the data # Acceptable values: # jpeg, png uint8[] data # Compressed image buffer ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id """ order = 0 migrated_types = [ ("Header","Header"),] valid = True def update(self, old_msg, new_msg): self.migrate(old_msg.header, new_msg.header) new_msg.format = old_msg.format new_msg.data = old_msg.uint8_data.data class update_laser_scan_LaserScan_90c7ef2dc6895d81024acba2ac42f369(MessageUpdateRule): old_type = "laser_scan/LaserScan" old_full_text = """ # # Laser scans angles are measured counter clockwise, with 0 facing forward # (along the x-axis) of the device frame # Header header float32 angle_min # start angle of the scan [rad] float32 angle_max # end angle of the scan [rad] float32 angle_increment # angular distance between measurements [rad] float32 time_increment # time between measurements [seconds] float32 scan_time # time between scans [seconds] float32 range_min # minimum range value [m] float32 range_max # maximum range value [m] float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded) float32[] intensities # intensity data [device-specific units] ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id """ new_type = "sensor_msgs/LaserScan" new_full_text = """ # Single scan from a planar laser range-finder # # If you have another ranging device with different behavior (e.g. a sonar # array), please find or create a different message, since applications # will make fairly laser-specific assumptions about this data Header header # timestamp in the header is the acquisition time of # the first ray in the scan. # # in frame frame_id, laser is assumed to spin around # the positive Z axis (counterclockwise, if Z is up) # with zero angle being forward along the x axis float32 angle_min # start angle of the scan [rad] float32 angle_max # end angle of the scan [rad] float32 angle_increment # angular distance between measurements [rad] float32 time_increment # time between measurements [seconds] - if your scanner # is moving, this will be used in interpolating position # of 3d points float32 scan_time # time between scans [seconds] float32 range_min # minimum range value [m] float32 range_max # maximum range value [m] float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded) float32[] intensities # intensity data [device-specific units]. If your # device does not provide intensities, please leave # the array empty. ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id """ order = 0 migrated_types = [ ("Header","Header"),] valid = True def update(self, old_msg, new_msg): self.migrate(old_msg.header, new_msg.header) new_msg.angle_min = old_msg.angle_min new_msg.angle_max = old_msg.angle_max new_msg.angle_increment = old_msg.angle_increment new_msg.time_increment = old_msg.time_increment new_msg.scan_time = old_msg.scan_time new_msg.range_min = old_msg.range_min new_msg.range_max = old_msg.range_max new_msg.ranges = old_msg.ranges new_msg.intensities = old_msg.intensities class update_mechanism_msgs_JointStates_6def7c223229ab1e340258092e485703(MessageUpdateRule): old_type = "mechanism_msgs/JointStates" old_full_text = """ Header header mechanism_msgs/JointState[] joints ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id ================================================================================ MSG: mechanism_msgs/JointState string name float64 position float64 velocity float64 applied_effort float64 commanded_effort byte is_calibrated """ new_type = "sensor_msgs/JointState" new_full_text = """ Header header string[] name float64[] position float64[] velocity float64[] effort ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id """ order = 0 migrated_types = [ ("Header","Header"),] valid = True def update(self, old_msg, new_msg): self.migrate(old_msg.header, new_msg.header) new_msg.name = [j.name for j in old_msg.joints] new_msg.position = [j.position for j in old_msg.joints] new_msg.velocity = [j.velocity for j in old_msg.joints] new_msg.effort = [j.applied_effort for j in old_msg.joints] class update_sensor_msgs_PointCloud_c47b5cedd2b77d241b27547ed7624840(MessageUpdateRule): old_type = "sensor_msgs/PointCloud" old_full_text = """ Header header geometry_msgs/Point32[] pts ChannelFloat32[] chan ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id ================================================================================ MSG: geometry_msgs/Point32 float32 x float32 y float32 z ================================================================================ MSG: sensor_msgs/ChannelFloat32 string name float32[] vals """ new_type = "sensor_msgs/PointCloud" new_full_text = """ #This message holds a collection of 3d points, plus optional additional information about each point. #Each Point32 should be interpreted as a 3d point in the frame given in the header Header header geometry_msgs/Point32[] points #Array of 3d points ChannelFloat32[] channels #Each channel should have the same number of elements as points array, and the data in each channel should correspond 1:1 with each point ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id ================================================================================ MSG: geometry_msgs/Point32 # This contains the position of a point in free space(with 32 bits of precision). # It is recommeded to use Point wherever possible instead of Point32. # # This recommendation is to promote interoperability. # # This message is designed to take up less space when sending # lots of points at once, as in the case of a PointCloud. float32 x float32 y float32 z ================================================================================ MSG: sensor_msgs/ChannelFloat32 #This message is used by the PointCloud message to hold optional data associated with each point in the cloud #The length of the values array should be the same as the length of the points array in the PointCloud, and each value should be associated with the corresponding point string name #channel name should give semantics of the channel (e.g. "intensity" instead of "value") float32[] values #values array should have same number of elements as the associated PointCloud """ order = 0 migrated_types = [ ("Header","Header"), ("geometry_msgs/Point32","geometry_msgs/Point32"), ("ChannelFloat32","ChannelFloat32")] valid = True def update(self, old_msg, new_msg): self.migrate(old_msg.header, new_msg.header) self.migrate_array(old_msg.pts, new_msg.points, "geometry_msgs/Point32") self.migrate_array(old_msg.chan, new_msg.channels, "ChannelFloat32") class update_sensor_msgs_ChannelFloat32_61c47e4621e471c885edb248b5dcafd5(MessageUpdateRule): old_type = "sensor_msgs/ChannelFloat32" old_full_text = """ string name float32[] vals """ new_type = "sensor_msgs/ChannelFloat32" new_full_text = """ #This message is used by the PointCloud message to hold optional data associated with each point in the cloud #The length of the values array should be the same as the length of the points array in the PointCloud, and each value should be associated with the corresponding point string name #channel name should give semantics of the channel (e.g. "intensity" instead of "value") float32[] values #values array should have same number of elements as the associated PointCloud """ order = 0 migrated_types = [] valid = True def update(self, old_msg, new_msg): new_msg.name = old_msg.name new_msg.values = old_msg.vals class update_sensor_msgs_CameraInfo_1b5cf7f984c229b6141ceb3a955aa18f(MessageUpdateRule): old_type = "sensor_msgs/CameraInfo" old_full_text = """ # This message defines meta information for a camera. It should be in a # camera namespace and accompanied by up to 5 image topics named: # # image_raw, image, image_color, image_rect, and image_rect_color # # The meaning of the camera parameters are described in detail at # http://pr.willowgarage.com/wiki/Camera_Calibration. ########################## # Image acquisition info # ########################## # Time of image acquisition, camera coordinate frame ID Header header # Camera resolution in pixels uint32 height uint32 width # Region of interest (subwindow of full camera resolution), if applicable RegionOfInterest roi ######################## # Intrinsic parameters # ######################## # Distortion parameters: k1, k2, t1, t2, k3 # These model radial and tangential distortion of the camera. float64[5] D # 5x1 vector # Original camera matrix # Projects 3D points in the camera coordinate frame to 2D pixel # coordinates using the focal lengths (fx, fy) and principal point # (cx, cy): # [fx 0 cx] # K = [ 0 fy cy] # [ 0 0 1] float64[9] K # 3x3 row-major matrix ######################## # Extrinsic parameters # ######################## # Rectification matrix (stereo cameras only) # A homography which takes an image to the ideal stereo image plane # so that epipolar lines in both stereo images are parallel. float64[9] R # 3x3 row-major matrix # Projection/camera matrix # Projects 3D points in a world coordinate frame to 2D pixel coordinates. float64[12] P # 3x4 row-major matrix ================================================================================ MSG: roslib/Header #Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id ================================================================================ MSG: sensor_msgs/RegionOfInterest uint32 x_offset uint32 y_offset uint32 height uint32 width """ new_type = "sensor_msgs/CameraInfo" new_full_text = """ # This message defines meta information for a camera. It should be in a # camera namespace on topic "camera_info" and accompanied by up to five # image topics named: # # image_raw - raw data from the camera driver, possibly Bayer encoded # image - monochrome, distorted # image_color - color, distorted # image_rect - monochrome, rectified # image_rect_color - color, rectified # # The image_pipeline contains packages (image_proc, stereo_image_proc) # for producing the four processed image topics from image_raw and # camera_info. The meaning of the camera parameters are described in # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. # # The image_geometry package provides a user-friendly interface to # common operations using this meta information. If you want to, e.g., # project a 3d point into image coordinates, we strongly recommend # using image_geometry. # # If the camera is uncalibrated, the matrices D, K, R, P should be left # zeroed out. In particular, clients may assume that K[0] == 0.0 # indicates an uncalibrated camera. ####################################################################### # Image acquisition info # ####################################################################### # Time of image acquisition, camera coordinate frame ID Header header # Header timestamp should be acquisition time of image # Header frame_id should be optical frame of camera # origin of frame should be optical center of camera # +x should point to the right in the image # +y should point down in the image # +z should point into the plane of the image ####################################################################### # Calibration Parameters # ####################################################################### # These are fixed during camera calibration. Their values will be the # # same in all messages until the camera is recalibrated. Note that # # self-calibrating systems may "recalibrate" frequently. # # # # The internal parameters can be used to warp a raw (distorted) image # # to: # # 1. An undistorted image (requires D and K) # # 2. A rectified image (requires D, K, R) # # The projection matrix P projects 3D points into the rectified image.# ####################################################################### # The image dimensions with which the camera was calibrated. Normally # this will be the full camera resolution in pixels. uint32 height uint32 width # The distortion model used. Supported models are listed in # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a # simple model of radial and tangential distortion - is sufficent. string distortion_model # The distortion parameters, size depending on the distortion model. # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). float64[] D # Intrinsic camera matrix for the raw (distorted) images. # [fx 0 cx] # K = [ 0 fy cy] # [ 0 0 1] # Projects 3D points in the camera coordinate frame to 2D pixel # coordinates using the focal lengths (fx, fy) and principal point # (cx, cy). float64[9] K # 3x3 row-major matrix # Rectification matrix (stereo cameras only) # A rotation matrix aligning the camera coordinate system to the ideal # stereo image plane so that epipolar lines in both stereo images are # parallel. float64[9] R # 3x3 row-major matrix # Projection/camera matrix # [fx' 0 cx' Tx] # P = [ 0 fy' cy' Ty] # [ 0 0 1 0] # By convention, this matrix specifies the intrinsic (camera) matrix # of the processed (rectified) image. That is, the left 3x3 portion # is the normal camera intrinsic matrix for the rectified image. # It projects 3D points in the camera coordinate frame to 2D pixel # coordinates using the focal lengths (fx', fy') and principal point # (cx', cy') - these may differ from the values in K. # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will # also have R = the identity and P[1:3,1:3] = K. # For a stereo pair, the fourth column [Tx Ty 0]' is related to the # position of the optical center of the second camera in the first # camera's frame. We assume Tz = 0 so both cameras are in the same # stereo image plane. The first camera always has Tx = Ty = 0. For # the right (second) camera of a horizontal stereo pair, Ty = 0 and # Tx = -fx' * B, where B is the baseline between the cameras. # Given a 3D point [X Y Z]', the projection (x, y) of the point onto # the rectified image is given by: # [u v w]' = P * [X Y Z 1]' # x = u / w # y = v / w # This holds for both images of a stereo pair. float64[12] P # 3x4 row-major matrix ####################################################################### # Operational Parameters # ####################################################################### # These define the image region actually captured by the camera # # driver. Although they affect the geometry of the output image, they # # may be changed freely without recalibrating the camera. # ####################################################################### # Binning refers here to any camera setting which combines rectangular # neighborhoods of pixels into larger "super-pixels." It reduces the # resolution of the output image to # (width / binning_x) x (height / binning_y). # The default values binning_x = binning_y = 0 is considered the same # as binning_x = binning_y = 1 (no subsampling). uint32 binning_x uint32 binning_y # Region of interest (subwindow of full camera resolution), given in # full resolution (unbinned) image coordinates. A particular ROI # always denotes the same window of pixels on the camera sensor, # regardless of binning settings. # The default setting of roi (all values 0) is considered the same as # full resolution (roi.width = width, roi.height = height). RegionOfInterest roi ================================================================================ MSG: roslib/Header # Standard metadata for higher-level stamped data types. # This is generally used to communicate timestamped data # in a particular coordinate frame. # # sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id ================================================================================ MSG: sensor_msgs/RegionOfInterest # This message is used to specify a region of interest within an image. # # When used to specify the ROI setting of the camera when the image was # taken, the height and width fields should either match the height and # width fields for the associated image; or height = width = 0 # indicates that the full resolution image was captured. uint32 x_offset # Leftmost pixel of the ROI # (0 if the ROI includes the left edge of the image) uint32 y_offset # Topmost pixel of the ROI # (0 if the ROI includes the top edge of the image) uint32 height # Height of ROI uint32 width # Width of ROI # True if a distinct rectified ROI should be calculated from the "raw" # ROI in this message. Typically this should be False if the full image # is captured (ROI not used), and True if a subwindow is captured (ROI # used). bool do_rectify """ order = 1 migrated_types = [ ("Header","Header"), ("RegionOfInterest","RegionOfInterest"),] valid = True def update(self, old_msg, new_msg): self.migrate(old_msg.header, new_msg.header) new_msg.height = old_msg.height new_msg.width = old_msg.width #No matching field name in old message new_msg.distortion_model = 'plumb_bob' #Converted from fixed array of length 5 to variable length new_msg.D = old_msg.D new_msg.K = old_msg.K new_msg.R = old_msg.R new_msg.P = old_msg.P #No matching field name in old message new_msg.binning_x = 1 #No matching field name in old message new_msg.binning_y = 1 self.migrate(old_msg.roi, new_msg.roi) # Set do_rectify True if ROI is not full resolution new_msg.roi.do_rectify = (new_msg.roi.width > 0 and new_msg.roi.width < new_msg.width) or \ (new_msg.roi.height > 0 and new_msg.roi.height < new_msg.height) class update_sensor_msgs_RegionOfInterest_878e60591f2679769082130f7aafa371(MessageUpdateRule): old_type = "sensor_msgs/RegionOfInterest" old_full_text = """ uint32 x_offset uint32 y_offset uint32 height uint32 width """ new_type = "sensor_msgs/RegionOfInterest" new_full_text = """ # This message is used to specify a region of interest within an image. # # When used to specify the ROI setting of the camera when the image was # taken, the height and width fields should either match the height and # width fields for the associated image; or height = width = 0 # indicates that the full resolution image was captured. uint32 x_offset # Leftmost pixel of the ROI # (0 if the ROI includes the left edge of the image) uint32 y_offset # Topmost pixel of the ROI # (0 if the ROI includes the top edge of the image) uint32 height # Height of ROI uint32 width # Width of ROI # True if a distinct rectified ROI should be calculated from the "raw" # ROI in this message. Typically this should be False if the full image # is captured (ROI not used), and True if a subwindow is captured (ROI # used). bool do_rectify """ order = 0 migrated_types = [] valid = True def update(self, old_msg, new_msg): new_msg.x_offset = old_msg.x_offset new_msg.y_offset = old_msg.y_offset new_msg.height = old_msg.height new_msg.width = old_msg.width #No matching field name in old message # We default to the old behavior here. do_rectify is actually set in the # CameraInfo update rule, which knows the full-res height/width. new_msg.do_rectify = False ros-common-msgs-1.12.7/sensor_msgs/msg/000077500000000000000000000000001337176563300200105ustar00rootroot00000000000000ros-common-msgs-1.12.7/sensor_msgs/msg/BatteryState.msg000066400000000000000000000044121337176563300231340ustar00rootroot00000000000000 # Constants are chosen to match the enums in the linux kernel # defined in include/linux/power_supply.h as of version 3.7 # The one difference is for style reasons the constants are # all uppercase not mixed case. # Power supply status constants uint8 POWER_SUPPLY_STATUS_UNKNOWN = 0 uint8 POWER_SUPPLY_STATUS_CHARGING = 1 uint8 POWER_SUPPLY_STATUS_DISCHARGING = 2 uint8 POWER_SUPPLY_STATUS_NOT_CHARGING = 3 uint8 POWER_SUPPLY_STATUS_FULL = 4 # Power supply health constants uint8 POWER_SUPPLY_HEALTH_UNKNOWN = 0 uint8 POWER_SUPPLY_HEALTH_GOOD = 1 uint8 POWER_SUPPLY_HEALTH_OVERHEAT = 2 uint8 POWER_SUPPLY_HEALTH_DEAD = 3 uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4 uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5 uint8 POWER_SUPPLY_HEALTH_COLD = 6 uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7 uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8 # Power supply technology (chemistry) constants uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0 uint8 POWER_SUPPLY_TECHNOLOGY_NIMH = 1 uint8 POWER_SUPPLY_TECHNOLOGY_LION = 2 uint8 POWER_SUPPLY_TECHNOLOGY_LIPO = 3 uint8 POWER_SUPPLY_TECHNOLOGY_LIFE = 4 uint8 POWER_SUPPLY_TECHNOLOGY_NICD = 5 uint8 POWER_SUPPLY_TECHNOLOGY_LIMN = 6 Header header float32 voltage # Voltage in Volts (Mandatory) float32 current # Negative when discharging (A) (If unmeasured NaN) float32 charge # Current charge in Ah (If unmeasured NaN) float32 capacity # Capacity in Ah (last full capacity) (If unmeasured NaN) float32 design_capacity # Capacity in Ah (design capacity) (If unmeasured NaN) float32 percentage # Charge percentage on 0 to 1 range (If unmeasured NaN) uint8 power_supply_status # The charging status as reported. Values defined above uint8 power_supply_health # The battery health metric. Values defined above uint8 power_supply_technology # The battery chemistry. Values defined above bool present # True if the battery is present float32[] cell_voltage # An array of individual cell voltages for each cell in the pack # If individual voltages unknown but number of cells known set each to NaN string location # The location into which the battery is inserted. (slot number or plug) string serial_number # The best approximation of the battery serial number ros-common-msgs-1.12.7/sensor_msgs/msg/CameraInfo.msg000066400000000000000000000142141337176563300225260ustar00rootroot00000000000000# This message defines meta information for a camera. It should be in a # camera namespace on topic "camera_info" and accompanied by up to five # image topics named: # # image_raw - raw data from the camera driver, possibly Bayer encoded # image - monochrome, distorted # image_color - color, distorted # image_rect - monochrome, rectified # image_rect_color - color, rectified # # The image_pipeline contains packages (image_proc, stereo_image_proc) # for producing the four processed image topics from image_raw and # camera_info. The meaning of the camera parameters are described in # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. # # The image_geometry package provides a user-friendly interface to # common operations using this meta information. If you want to, e.g., # project a 3d point into image coordinates, we strongly recommend # using image_geometry. # # If the camera is uncalibrated, the matrices D, K, R, P should be left # zeroed out. In particular, clients may assume that K[0] == 0.0 # indicates an uncalibrated camera. ####################################################################### # Image acquisition info # ####################################################################### # Time of image acquisition, camera coordinate frame ID Header header # Header timestamp should be acquisition time of image # Header frame_id should be optical frame of camera # origin of frame should be optical center of camera # +x should point to the right in the image # +y should point down in the image # +z should point into the plane of the image ####################################################################### # Calibration Parameters # ####################################################################### # These are fixed during camera calibration. Their values will be the # # same in all messages until the camera is recalibrated. Note that # # self-calibrating systems may "recalibrate" frequently. # # # # The internal parameters can be used to warp a raw (distorted) image # # to: # # 1. An undistorted image (requires D and K) # # 2. A rectified image (requires D, K, R) # # The projection matrix P projects 3D points into the rectified image.# ####################################################################### # The image dimensions with which the camera was calibrated. Normally # this will be the full camera resolution in pixels. uint32 height uint32 width # The distortion model used. Supported models are listed in # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a # simple model of radial and tangential distortion - is sufficient. string distortion_model # The distortion parameters, size depending on the distortion model. # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). float64[] D # Intrinsic camera matrix for the raw (distorted) images. # [fx 0 cx] # K = [ 0 fy cy] # [ 0 0 1] # Projects 3D points in the camera coordinate frame to 2D pixel # coordinates using the focal lengths (fx, fy) and principal point # (cx, cy). float64[9] K # 3x3 row-major matrix # Rectification matrix (stereo cameras only) # A rotation matrix aligning the camera coordinate system to the ideal # stereo image plane so that epipolar lines in both stereo images are # parallel. float64[9] R # 3x3 row-major matrix # Projection/camera matrix # [fx' 0 cx' Tx] # P = [ 0 fy' cy' Ty] # [ 0 0 1 0] # By convention, this matrix specifies the intrinsic (camera) matrix # of the processed (rectified) image. That is, the left 3x3 portion # is the normal camera intrinsic matrix for the rectified image. # It projects 3D points in the camera coordinate frame to 2D pixel # coordinates using the focal lengths (fx', fy') and principal point # (cx', cy') - these may differ from the values in K. # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will # also have R = the identity and P[1:3,1:3] = K. # For a stereo pair, the fourth column [Tx Ty 0]' is related to the # position of the optical center of the second camera in the first # camera's frame. We assume Tz = 0 so both cameras are in the same # stereo image plane. The first camera always has Tx = Ty = 0. For # the right (second) camera of a horizontal stereo pair, Ty = 0 and # Tx = -fx' * B, where B is the baseline between the cameras. # Given a 3D point [X Y Z]', the projection (x, y) of the point onto # the rectified image is given by: # [u v w]' = P * [X Y Z 1]' # x = u / w # y = v / w # This holds for both images of a stereo pair. float64[12] P # 3x4 row-major matrix ####################################################################### # Operational Parameters # ####################################################################### # These define the image region actually captured by the camera # # driver. Although they affect the geometry of the output image, they # # may be changed freely without recalibrating the camera. # ####################################################################### # Binning refers here to any camera setting which combines rectangular # neighborhoods of pixels into larger "super-pixels." It reduces the # resolution of the output image to # (width / binning_x) x (height / binning_y). # The default values binning_x = binning_y = 0 is considered the same # as binning_x = binning_y = 1 (no subsampling). uint32 binning_x uint32 binning_y # Region of interest (subwindow of full camera resolution), given in # full resolution (unbinned) image coordinates. A particular ROI # always denotes the same window of pixels on the camera sensor, # regardless of binning settings. # The default setting of roi (all values 0) is considered the same as # full resolution (roi.width = width, roi.height = height). RegionOfInterest roi ros-common-msgs-1.12.7/sensor_msgs/msg/ChannelFloat32.msg000066400000000000000000000017601337176563300232270ustar00rootroot00000000000000# This message is used by the PointCloud message to hold optional data # associated with each point in the cloud. The length of the values # array should be the same as the length of the points array in the # PointCloud, and each value should be associated with the corresponding # point. # Channel names in existing practice include: # "u", "v" - row and column (respectively) in the left stereo image. # This is opposite to usual conventions but remains for # historical reasons. The newer PointCloud2 message has no # such problem. # "rgb" - For point clouds produced by color stereo cameras. uint8 # (R,G,B) values packed into the least significant 24 bits, # in order. # "intensity" - laser or pixel intensity. # "distance" # The channel name should give semantics of the channel (e.g. # "intensity" instead of "value"). string name # The values array should be 1-1 with the elements of the associated # PointCloud. float32[] values ros-common-msgs-1.12.7/sensor_msgs/msg/CompressedImage.msg000066400000000000000000000012001337176563300235600ustar00rootroot00000000000000# This message contains a compressed image Header header # Header timestamp should be acquisition time of image # Header frame_id should be optical frame of camera # origin of frame should be optical center of camera # +x should point to the right in the image # +y should point down in the image # +z should point into to plane of the image string format # Specifies the format of the data # Acceptable values: # jpeg, png uint8[] data # Compressed image buffer ros-common-msgs-1.12.7/sensor_msgs/msg/FluidPressure.msg000066400000000000000000000010051337176563300233100ustar00rootroot00000000000000 # Single pressure reading. This message is appropriate for measuring the # pressure inside of a fluid (air, water, etc). This also includes # atmospheric or barometric pressure. # This message is not appropriate for force/pressure contact sensors. Header header # timestamp of the measurement # frame_id is the location of the pressure sensor float64 fluid_pressure # Absolute pressure reading in Pascals. float64 variance # 0 is interpreted as variance unknownros-common-msgs-1.12.7/sensor_msgs/msg/Illuminance.msg000066400000000000000000000017321337176563300227630ustar00rootroot00000000000000 # Single photometric illuminance measurement. Light should be assumed to be # measured along the sensor's x-axis (the area of detection is the y-z plane). # The illuminance should have a 0 or positive value and be received with # the sensor's +X axis pointing toward the light source. # Photometric illuminance is the measure of the human eye's sensitivity of the # intensity of light encountering or passing through a surface. # All other Photometric and Radiometric measurements should # not use this message. # This message cannot represent: # Luminous intensity (candela/light source output) # Luminance (nits/light output per area) # Irradiance (watt/area), etc. Header header # timestamp is the time the illuminance was measured # frame_id is the location and direction of the reading float64 illuminance # Measurement of the Photometric Illuminance in Lux. float64 variance # 0 is interpreted as variance unknownros-common-msgs-1.12.7/sensor_msgs/msg/Image.msg000066400000000000000000000025221337176563300215430ustar00rootroot00000000000000# This message contains an uncompressed image # (0, 0) is at top-left corner of image # Header header # Header timestamp should be acquisition time of image # Header frame_id should be optical frame of camera # origin of frame should be optical center of camera # +x should point to the right in the image # +y should point down in the image # +z should point into to plane of the image # If the frame_id here and the frame_id of the CameraInfo # message associated with the image conflict # the behavior is undefined uint32 height # image height, that is, number of rows uint32 width # image width, that is, number of columns # The legal values for encoding are in file src/image_encodings.cpp # If you want to standardize a new string format, join # ros-users@lists.sourceforge.net and send an email proposing a new encoding. string encoding # Encoding of pixels -- channel meaning, ordering, size # taken from the list of strings in include/sensor_msgs/image_encodings.h uint8 is_bigendian # is this data bigendian? uint32 step # Full row length in bytes uint8[] data # actual matrix data, size is (step * rows) ros-common-msgs-1.12.7/sensor_msgs/msg/Imu.msg000066400000000000000000000022661337176563300212600ustar00rootroot00000000000000# This is a message to hold data from an IMU (Inertial Measurement Unit) # # Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec # # If the covariance of the measurement is known, it should be filled in (if all you know is the # variance of each measurement, e.g. from the datasheet, just put those along the diagonal) # A covariance matrix of all zeros will be interpreted as "covariance unknown", and to use the # data a covariance will have to be assumed or gotten from some other source # # If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation # estimate), please set element 0 of the associated covariance matrix to -1 # If you are interpreting this message, please check for a value of -1 in the first element of each # covariance matrix, and disregard the associated estimate. Header header geometry_msgs/Quaternion orientation float64[9] orientation_covariance # Row major about x, y, z axes geometry_msgs/Vector3 angular_velocity float64[9] angular_velocity_covariance # Row major about x, y, z axes geometry_msgs/Vector3 linear_acceleration float64[9] linear_acceleration_covariance # Row major x, y z ros-common-msgs-1.12.7/sensor_msgs/msg/JointState.msg000066400000000000000000000017431337176563300226110ustar00rootroot00000000000000# This is a message that holds data to describe the state of a set of torque controlled joints. # # The state of each joint (revolute or prismatic) is defined by: # * the position of the joint (rad or m), # * the velocity of the joint (rad/s or m/s) and # * the effort that is applied in the joint (Nm or N). # # Each joint is uniquely identified by its name # The header specifies the time at which the joint states were recorded. All the joint states # in one message have to be recorded at the same time. # # This message consists of a multiple arrays, one for each part of the joint state. # The goal is to make each of the fields optional. When e.g. your joints have no # effort associated with them, you can leave the effort array empty. # # All arrays in this message should have the same size, or be empty. # This is the only way to uniquely associate the joint name with the correct # states. Header header string[] name float64[] position float64[] velocity float64[] effort ros-common-msgs-1.12.7/sensor_msgs/msg/Joy.msg000066400000000000000000000004361337176563300212640ustar00rootroot00000000000000# Reports the state of a joysticks axes and buttons. Header header # timestamp in the header is the time the data is received from the joystick float32[] axes # the axes measurements from a joystick int32[] buttons # the buttons measurements from a joystick ros-common-msgs-1.12.7/sensor_msgs/msg/JoyFeedback.msg000066400000000000000000000006351337176563300226720ustar00rootroot00000000000000# Declare of the type of feedback uint8 TYPE_LED = 0 uint8 TYPE_RUMBLE = 1 uint8 TYPE_BUZZER = 2 uint8 type # This will hold an id number for each type of each feedback. # Example, the first led would be id=0, the second would be id=1 uint8 id # Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is # actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on. float32 intensity ros-common-msgs-1.12.7/sensor_msgs/msg/JoyFeedbackArray.msg000066400000000000000000000001231337176563300236610ustar00rootroot00000000000000# This message publishes values for multiple feedback at once. JoyFeedback[] arrayros-common-msgs-1.12.7/sensor_msgs/msg/LaserEcho.msg000066400000000000000000000003561337176563300223710ustar00rootroot00000000000000# This message is a submessage of MultiEchoLaserScan and is not intended # to be used separately. float32[] echoes # Multiple values of ranges or intensities. # Each array represents data from the same angle increment.ros-common-msgs-1.12.7/sensor_msgs/msg/LaserScan.msg000066400000000000000000000027571337176563300224060ustar00rootroot00000000000000# Single scan from a planar laser range-finder # # If you have another ranging device with different behavior (e.g. a sonar # array), please find or create a different message, since applications # will make fairly laser-specific assumptions about this data Header header # timestamp in the header is the acquisition time of # the first ray in the scan. # # in frame frame_id, angles are measured around # the positive Z axis (counterclockwise, if Z is up) # with zero angle being forward along the x axis float32 angle_min # start angle of the scan [rad] float32 angle_max # end angle of the scan [rad] float32 angle_increment # angular distance between measurements [rad] float32 time_increment # time between measurements [seconds] - if your scanner # is moving, this will be used in interpolating position # of 3d points float32 scan_time # time between scans [seconds] float32 range_min # minimum range value [m] float32 range_max # maximum range value [m] float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded) float32[] intensities # intensity data [device-specific units]. If your # device does not provide intensities, please leave # the array empty. ros-common-msgs-1.12.7/sensor_msgs/msg/MagneticField.msg000066400000000000000000000021761337176563300232210ustar00rootroot00000000000000 # Measurement of the Magnetic Field vector at a specific location. # If the covariance of the measurement is known, it should be filled in # (if all you know is the variance of each measurement, e.g. from the datasheet, #just put those along the diagonal) # A covariance matrix of all zeros will be interpreted as "covariance unknown", # and to use the data a covariance will have to be assumed or gotten from some # other source Header header # timestamp is the time the # field was measured # frame_id is the location and orientation # of the field measurement geometry_msgs/Vector3 magnetic_field # x, y, and z components of the # field vector in Tesla # If your sensor does not output 3 axes, # put NaNs in the components not reported. float64[9] magnetic_field_covariance # Row major about x, y, z axes # 0 is interpreted as variance unknownros-common-msgs-1.12.7/sensor_msgs/msg/MultiDOFJointState.msg000066400000000000000000000021771337176563300241570ustar00rootroot00000000000000# Representation of state for joints with multiple degrees of freedom, # following the structure of JointState. # # It is assumed that a joint in a system corresponds to a transform that gets applied # along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw) # and those 3DOF can be expressed as a transformation matrix, and that transformation # matrix can be converted back to (x, y, yaw) # # Each joint is uniquely identified by its name # The header specifies the time at which the joint states were recorded. All the joint states # in one message have to be recorded at the same time. # # This message consists of a multiple arrays, one for each part of the joint state. # The goal is to make each of the fields optional. When e.g. your joints have no # wrench associated with them, you can leave the wrench array empty. # # All arrays in this message should have the same size, or be empty. # This is the only way to uniquely associate the joint name with the correct # states. Header header string[] joint_names geometry_msgs/Transform[] transforms geometry_msgs/Twist[] twist geometry_msgs/Wrench[] wrench ros-common-msgs-1.12.7/sensor_msgs/msg/MultiEchoLaserScan.msg000066400000000000000000000032251337176563300242070ustar00rootroot00000000000000# Single scan from a multi-echo planar laser range-finder # # If you have another ranging device with different behavior (e.g. a sonar # array), please find or create a different message, since applications # will make fairly laser-specific assumptions about this data Header header # timestamp in the header is the acquisition time of # the first ray in the scan. # # in frame frame_id, angles are measured around # the positive Z axis (counterclockwise, if Z is up) # with zero angle being forward along the x axis float32 angle_min # start angle of the scan [rad] float32 angle_max # end angle of the scan [rad] float32 angle_increment # angular distance between measurements [rad] float32 time_increment # time between measurements [seconds] - if your scanner # is moving, this will be used in interpolating position # of 3d points float32 scan_time # time between scans [seconds] float32 range_min # minimum range value [m] float32 range_max # maximum range value [m] LaserEcho[] ranges # range data [m] (Note: NaNs, values < range_min or > range_max should be discarded) # +Inf measurements are out of range # -Inf measurements are too close to determine exact distance. LaserEcho[] intensities # intensity data [device-specific units]. If your # device does not provide intensities, please leave # the array empty.ros-common-msgs-1.12.7/sensor_msgs/msg/NavSatFix.msg000066400000000000000000000030741337176563300223670ustar00rootroot00000000000000# Navigation Satellite fix for any Global Navigation Satellite System # # Specified using the WGS 84 reference ellipsoid # header.stamp specifies the ROS time for this measurement (the # corresponding satellite time may be reported using the # sensor_msgs/TimeReference message). # # header.frame_id is the frame of reference reported by the satellite # receiver, usually the location of the antenna. This is a # Euclidean frame relative to the vehicle, not a reference # ellipsoid. Header header # satellite fix status information NavSatStatus status # Latitude [degrees]. Positive is north of equator; negative is south. float64 latitude # Longitude [degrees]. Positive is east of prime meridian; negative is west. float64 longitude # Altitude [m]. Positive is above the WGS 84 ellipsoid # (quiet NaN if no altitude is available). float64 altitude # Position covariance [m^2] defined relative to a tangential plane # through the reported position. The components are East, North, and # Up (ENU), in row-major order. # # Beware: this coordinate system exhibits singularities at the poles. float64[9] position_covariance # If the covariance of the fix is known, fill it in completely. If the # GPS receiver provides the variance of each measurement, put them # along the diagonal. If only Dilution of Precision is available, # estimate an approximate covariance from that. uint8 COVARIANCE_TYPE_UNKNOWN = 0 uint8 COVARIANCE_TYPE_APPROXIMATED = 1 uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2 uint8 COVARIANCE_TYPE_KNOWN = 3 uint8 position_covariance_type ros-common-msgs-1.12.7/sensor_msgs/msg/NavSatStatus.msg000066400000000000000000000013611337176563300231210ustar00rootroot00000000000000# Navigation Satellite fix status for any Global Navigation Satellite System # Whether to output an augmented fix is determined by both the fix # type and the last time differential corrections were received. A # fix is valid when status >= STATUS_FIX. int8 STATUS_NO_FIX = -1 # unable to fix position int8 STATUS_FIX = 0 # unaugmented fix int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation int8 status # Bits defining which Global Navigation Satellite System signals were # used by the receiver. uint16 SERVICE_GPS = 1 uint16 SERVICE_GLONASS = 2 uint16 SERVICE_COMPASS = 4 # includes BeiDou. uint16 SERVICE_GALILEO = 8 uint16 service ros-common-msgs-1.12.7/sensor_msgs/msg/PointCloud.msg000066400000000000000000000010511337176563300225750ustar00rootroot00000000000000# This message holds a collection of 3d points, plus optional additional # information about each point. # Time of sensor data acquisition, coordinate frame ID. Header header # Array of 3d points. Each Point32 should be interpreted as a 3d point # in the frame given in the header. geometry_msgs/Point32[] points # Each channel should have the same number of elements as points array, # and the data in each channel should correspond 1:1 with each point. # Channel names in common practice are listed in ChannelFloat32.msg. ChannelFloat32[] channels ros-common-msgs-1.12.7/sensor_msgs/msg/PointCloud2.msg000066400000000000000000000020171337176563300226620ustar00rootroot00000000000000# This message holds a collection of N-dimensional points, which may # contain additional information such as normals, intensity, etc. The # point data is stored as a binary blob, its layout described by the # contents of the "fields" array. # The point cloud data may be organized 2d (image-like) or 1d # (unordered). Point clouds organized as 2d images may be produced by # camera depth sensors such as stereo or time-of-flight. # Time of sensor data acquisition, and the coordinate frame ID (for 3d # points). Header header # 2D structure of the point cloud. If the cloud is unordered, height is # 1 and width is the length of the point cloud. uint32 height uint32 width # Describes the channels and their layout in the binary data blob. PointField[] fields bool is_bigendian # Is this data bigendian? uint32 point_step # Length of a point in bytes uint32 row_step # Length of a row in bytes uint8[] data # Actual point data, size is (row_step*height) bool is_dense # True if there are no invalid points ros-common-msgs-1.12.7/sensor_msgs/msg/PointField.msg000066400000000000000000000006511337176563300225570ustar00rootroot00000000000000# This message holds the description of one point entry in the # PointCloud2 message format. uint8 INT8 = 1 uint8 UINT8 = 2 uint8 INT16 = 3 uint8 UINT16 = 4 uint8 INT32 = 5 uint8 UINT32 = 6 uint8 FLOAT32 = 7 uint8 FLOAT64 = 8 string name # Name of field uint32 offset # Offset from start of point struct uint8 datatype # Datatype enumeration, see above uint32 count # How many elements in the field ros-common-msgs-1.12.7/sensor_msgs/msg/Range.msg000066400000000000000000000037531337176563300215640ustar00rootroot00000000000000# Single range reading from an active ranger that emits energy and reports # one range reading that is valid along an arc at the distance measured. # This message is not appropriate for laser scanners. See the LaserScan # message if you are working with a laser scanner. # This message also can represent a fixed-distance (binary) ranger. This # sensor will have min_range===max_range===distance of detection. # These sensors follow REP 117 and will output -Inf if the object is detected # and +Inf if the object is outside of the detection range. Header header # timestamp in the header is the time the ranger # returned the distance reading # Radiation type enums # If you want a value added to this list, send an email to the ros-users list uint8 ULTRASOUND=0 uint8 INFRARED=1 uint8 radiation_type # the type of radiation used by the sensor # (sound, IR, etc) [enum] float32 field_of_view # the size of the arc that the distance reading is # valid for [rad] # the object causing the range reading may have # been anywhere within -field_of_view/2 and # field_of_view/2 at the measured range. # 0 angle corresponds to the x-axis of the sensor. float32 min_range # minimum range value [m] float32 max_range # maximum range value [m] # Fixed distance rangers require min_range==max_range float32 range # range data [m] # (Note: values < range_min or > range_max # should be discarded) # Fixed distance rangers only output -Inf or +Inf. # -Inf represents a detection within fixed distance. # (Detection too close to the sensor to quantify) # +Inf represents no detection within the fixed distance. # (Object out of range)ros-common-msgs-1.12.7/sensor_msgs/msg/RegionOfInterest.msg000066400000000000000000000015501337176563300237470ustar00rootroot00000000000000# This message is used to specify a region of interest within an image. # # When used to specify the ROI setting of the camera when the image was # taken, the height and width fields should either match the height and # width fields for the associated image; or height = width = 0 # indicates that the full resolution image was captured. uint32 x_offset # Leftmost pixel of the ROI # (0 if the ROI includes the left edge of the image) uint32 y_offset # Topmost pixel of the ROI # (0 if the ROI includes the top edge of the image) uint32 height # Height of ROI uint32 width # Width of ROI # True if a distinct rectified ROI should be calculated from the "raw" # ROI in this message. Typically this should be False if the full image # is captured (ROI not used), and True if a subwindow is captured (ROI # used). bool do_rectify ros-common-msgs-1.12.7/sensor_msgs/msg/RelativeHumidity.msg000066400000000000000000000011521337176563300240070ustar00rootroot00000000000000 # Single reading from a relative humidity sensor. Defines the ratio of partial # pressure of water vapor to the saturated vapor pressure at a temperature. Header header # timestamp of the measurement # frame_id is the location of the humidity sensor float64 relative_humidity # Expression of the relative humidity # from 0.0 to 1.0. # 0.0 is no partial pressure of water vapor # 1.0 represents partial pressure of saturation float64 variance # 0 is interpreted as variance unknownros-common-msgs-1.12.7/sensor_msgs/msg/Temperature.msg000066400000000000000000000005131337176563300230140ustar00rootroot00000000000000 # Single temperature reading. Header header # timestamp is the time the temperature was measured # frame_id is the location of the temperature reading float64 temperature # Measurement of the Temperature in Degrees Celsius float64 variance # 0 is interpreted as variance unknownros-common-msgs-1.12.7/sensor_msgs/msg/TimeReference.msg000066400000000000000000000005011337176563300232310ustar00rootroot00000000000000# Measurement from an external time source not actively synchronized with the system clock. Header header # stamp is system time for which measurement was valid # frame_id is not used time time_ref # corresponding time from this external source string source # (optional) name of time source ros-common-msgs-1.12.7/sensor_msgs/package.xml000066400000000000000000000015471337176563300213460ustar00rootroot00000000000000 sensor_msgs 1.12.7 This package defines messages for commonly used sensors, including cameras and scanning laser rangefinders. Tully Foote BSD http://ros.org/wiki/sensor_msgs catkin geometry_msgs message_generation std_msgs geometry_msgs message_runtime std_msgs rosbag rosunit ros-common-msgs-1.12.7/sensor_msgs/setup.py000066400000000000000000000004751337176563300207420ustar00rootroot00000000000000#!/usr/bin/env python from distutils.core import setup from catkin_pkg.python_setup import generate_distutils_setup d = generate_distutils_setup( ## don't do this unless you want a globally visible script # scripts=['bin/myscript'], packages=['sensor_msgs'], package_dir={'': 'src'} ) setup(**d) ros-common-msgs-1.12.7/sensor_msgs/src/000077500000000000000000000000001337176563300200115ustar00rootroot00000000000000ros-common-msgs-1.12.7/sensor_msgs/src/sensor_msgs/000077500000000000000000000000001337176563300223535ustar00rootroot00000000000000ros-common-msgs-1.12.7/sensor_msgs/src/sensor_msgs/__init__.py000066400000000000000000000000001337176563300244520ustar00rootroot00000000000000ros-common-msgs-1.12.7/sensor_msgs/src/sensor_msgs/point_cloud2.py000066400000000000000000000203001337176563300253210ustar00rootroot00000000000000#!/usr/bin/env python # Software License Agreement (BSD License) # # Copyright (c) 2008, Willow Garage, Inc. # All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions # are met: # # * Redistributions of source code must retain the above copyright # notice, this list of conditions and the following disclaimer. # * Redistributions in binary form must reproduce the above # copyright notice, this list of conditions and the following # disclaimer in the documentation and/or other materials provided # with the distribution. # * Neither the name of Willow Garage, Inc. nor the names of its # contributors may be used to endorse or promote products derived # from this software without specific prior written permission. # # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE # POSSIBILITY OF SUCH DAMAGE. from __future__ import print_function """ Serialization of sensor_msgs.PointCloud2 messages. Author: Tim Field """ from collections import namedtuple import ctypes import math import struct import roslib.message from sensor_msgs.msg import PointCloud2, PointField _DATATYPES = {} _DATATYPES[PointField.INT8] = ('b', 1) _DATATYPES[PointField.UINT8] = ('B', 1) _DATATYPES[PointField.INT16] = ('h', 2) _DATATYPES[PointField.UINT16] = ('H', 2) _DATATYPES[PointField.INT32] = ('i', 4) _DATATYPES[PointField.UINT32] = ('I', 4) _DATATYPES[PointField.FLOAT32] = ('f', 4) _DATATYPES[PointField.FLOAT64] = ('d', 8) def read_points(cloud, field_names=None, skip_nans=False, uvs=[]): """ Read points from a L{sensor_msgs.PointCloud2} message. @param cloud: The point cloud to read from. @type cloud: L{sensor_msgs.PointCloud2} @param field_names: The names of fields to read. If None, read all fields. [default: None] @type field_names: iterable @param skip_nans: If True, then don't return any point with a NaN value. @type skip_nans: bool [default: False] @param uvs: If specified, then only return the points at the given coordinates. [default: empty list] @type uvs: iterable @return: Generator which yields a list of values for each point. @rtype: generator """ assert isinstance(cloud, roslib.message.Message) and cloud._type == 'sensor_msgs/PointCloud2', 'cloud is not a sensor_msgs.msg.PointCloud2' fmt = _get_struct_fmt(cloud.is_bigendian, cloud.fields, field_names) width, height, point_step, row_step, data, isnan = cloud.width, cloud.height, cloud.point_step, cloud.row_step, cloud.data, math.isnan unpack_from = struct.Struct(fmt).unpack_from if skip_nans: if uvs: for u, v in uvs: p = unpack_from(data, (row_step * v) + (point_step * u)) has_nan = False for pv in p: if isnan(pv): has_nan = True break if not has_nan: yield p else: for v in range(height): offset = row_step * v for u in range(width): p = unpack_from(data, offset) has_nan = False for pv in p: if isnan(pv): has_nan = True break if not has_nan: yield p offset += point_step else: if uvs: for u, v in uvs: yield unpack_from(data, (row_step * v) + (point_step * u)) else: for v in range(height): offset = row_step * v for u in range(width): yield unpack_from(data, offset) offset += point_step def read_points_list(cloud, field_names=None, skip_nans=False, uvs=[]): """ Read points from a L{sensor_msgs.PointCloud2} message. This function returns a list of namedtuples. It operates on top of the read_points method. For more efficient access use read_points directly. @param cloud: The point cloud to read from. @type cloud: L{sensor_msgs.PointCloud2} @param field_names: The names of fields to read. If None, read all fields. [default: None] @type field_names: iterable @param skip_nans: If True, then don't return any point with a NaN value. @type skip_nans: bool [default: False] @param uvs: If specified, then only return the points at the given coordinates. [default: empty list] @type uvs: iterable @return: List of namedtuples containing the values for each point @rtype: list """ assert isinstance(cloud, roslib.message.Message) and cloud._type == 'sensor_msgs/PointCloud2', 'cloud is not a sensor_msgs.msg.PointCloud2' if field_names is None: field_names = [f.name for f in cloud.fields] Point = namedtuple("Point", field_names) return [Point._make(l) for l in read_points(cloud, field_names, skip_nans, uvs)] def create_cloud(header, fields, points): """ Create a L{sensor_msgs.msg.PointCloud2} message. @param header: The point cloud header. @type header: L{std_msgs.msg.Header} @param fields: The point cloud fields. @type fields: iterable of L{sensor_msgs.msg.PointField} @param points: The point cloud points. @type points: list of iterables, i.e. one iterable for each point, with the elements of each iterable being the values of the fields for that point (in the same order as the fields parameter) @return: The point cloud. @rtype: L{sensor_msgs.msg.PointCloud2} """ cloud_struct = struct.Struct(_get_struct_fmt(False, fields)) buff = ctypes.create_string_buffer(cloud_struct.size * len(points)) point_step, pack_into = cloud_struct.size, cloud_struct.pack_into offset = 0 for p in points: pack_into(buff, offset, *p) offset += point_step return PointCloud2(header=header, height=1, width=len(points), is_dense=False, is_bigendian=False, fields=fields, point_step=cloud_struct.size, row_step=cloud_struct.size * len(points), data=buff.raw) def create_cloud_xyz32(header, points): """ Create a L{sensor_msgs.msg.PointCloud2} message with 3 float32 fields (x, y, z). @param header: The point cloud header. @type header: L{std_msgs.msg.Header} @param points: The point cloud points. @type points: iterable @return: The point cloud. @rtype: L{sensor_msgs.msg.PointCloud2} """ fields = [PointField('x', 0, PointField.FLOAT32, 1), PointField('y', 4, PointField.FLOAT32, 1), PointField('z', 8, PointField.FLOAT32, 1)] return create_cloud(header, fields, points) def _get_struct_fmt(is_bigendian, fields, field_names=None): fmt = '>' if is_bigendian else '<' offset = 0 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): if offset < field.offset: fmt += 'x' * (field.offset - offset) offset = field.offset if field.datatype not in _DATATYPES: print('Skipping unknown PointField datatype [%d]' % field.datatype, file=sys.stderr) else: datatype_fmt, datatype_length = _DATATYPES[field.datatype] fmt += field.count * datatype_fmt offset += field.count * datatype_length return fmt ros-common-msgs-1.12.7/sensor_msgs/srv/000077500000000000000000000000001337176563300200345ustar00rootroot00000000000000ros-common-msgs-1.12.7/sensor_msgs/srv/SetCameraInfo.srv000066400000000000000000000010601337176563300232450ustar00rootroot00000000000000# This service requests that a camera stores the given CameraInfo # as that camera's calibration information. # # The width and height in the camera_info field should match what the # camera is currently outputting on its camera_info topic, and the camera # will assume that the region of the imager that is being referred to is # the region that the camera is currently capturing. sensor_msgs/CameraInfo camera_info # The camera_info to store --- bool success # True if the call succeeded string status_message # Used to give details about success ros-common-msgs-1.12.7/sensor_msgs/test/000077500000000000000000000000001337176563300202015ustar00rootroot00000000000000ros-common-msgs-1.12.7/sensor_msgs/test/CMakeLists.txt000066400000000000000000000004321337176563300227400ustar00rootroot00000000000000include_directories(${catkin_INCLUDE_DIRS}) catkin_add_gtest(${PROJECT_NAME}_test main.cpp) catkin_add_gtest(${PROJECT_NAME}_test_image_encodings test_image_encodings.cpp) if(TARGET sensor_msgs_test) add_dependencies(${PROJECT_NAME}_test ${sensor_msgs_EXPORTED_TARGETS}) endif() ros-common-msgs-1.12.7/sensor_msgs/test/main.cpp000066400000000000000000000124251337176563300216350ustar00rootroot00000000000000/* * Software License Agreement (BSD License) * * Copyright (c) 2013, Open Source Robotics Foundation * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include #include TEST(sensor_msgs, PointCloud2Iterator) { // Create a dummy PointCloud2 int n_points = 4; sensor_msgs::PointCloud2 cloud_msg_1, cloud_msg_2; cloud_msg_1.height = n_points; cloud_msg_1.width = 1; sensor_msgs::PointCloud2Modifier modifier(cloud_msg_1); modifier.setPointCloud2FieldsByString(2, "xyz", "rgb"); cloud_msg_2 = cloud_msg_1; // Fill 1 by hand 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}; std::vector point_data(point_data_raw, point_data_raw + 3*n_points); // colors in RGB order uint8_t color_data_raw[] = {40, 80, 120, 160, 200, 240, 20, 40, 60, 80, 100, 120}; std::vector color_data(color_data_raw, color_data_raw + 3*n_points); float *data = reinterpret_cast(&cloud_msg_1.data.front()); for(size_t n=0, i=0; n(data++); // add the colors in order BGRA like PCL size_t j_max = 2; for(size_t j = 0; j <= j_max; ++j) *(bgr++) = color_data[3*n+(j_max - j)]; // Add 3 extra floats of padding data += 3; } // Fill 2 using an iterator sensor_msgs::PointCloud2Iterator iter_x(cloud_msg_2, "x"); sensor_msgs::PointCloud2Iterator iter_r(cloud_msg_2, "r"); sensor_msgs::PointCloud2Iterator iter_g(cloud_msg_2, "g"); sensor_msgs::PointCloud2Iterator iter_b(cloud_msg_2, "b"); for(size_t i=0; i iter_const_1_x(cloud_msg_1, "x"), iter_const_2_x(cloud_msg_2, "x"); sensor_msgs::PointCloud2ConstIterator iter_const_1_y(cloud_msg_1, "y"), iter_const_2_y(cloud_msg_2, "y"); sensor_msgs::PointCloud2ConstIterator iter_const_1_z(cloud_msg_1, "z"), iter_const_2_z(cloud_msg_2, "z"); sensor_msgs::PointCloud2ConstIterator iter_const_1_r(cloud_msg_1, "r"), iter_const_2_r(cloud_msg_2, "r"); sensor_msgs::PointCloud2ConstIterator iter_const_1_g(cloud_msg_1, "g"), iter_const_2_g(cloud_msg_2, "g"); sensor_msgs::PointCloud2ConstIterator iter_const_1_b(cloud_msg_1, "b"), iter_const_2_b(cloud_msg_2, "b"); size_t i=0; 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, ++iter_const_1_z, ++iter_const_2_z, ++iter_const_1_r, ++iter_const_1_g, ++iter_const_1_b) { EXPECT_EQ(*iter_const_1_x, *iter_const_2_x); EXPECT_EQ(*iter_const_1_x, point_data[0+3*i]); EXPECT_EQ(*iter_const_1_y, *iter_const_2_y); EXPECT_EQ(*iter_const_1_y, point_data[1+3*i]); EXPECT_EQ(*iter_const_1_z, *iter_const_2_z); EXPECT_EQ(*iter_const_1_z, point_data[2+3*i]); EXPECT_EQ(*iter_const_1_r, *iter_const_2_r); EXPECT_EQ(*iter_const_1_r, color_data[3*i+0]); EXPECT_EQ(*iter_const_1_g, *iter_const_2_g); EXPECT_EQ(*iter_const_1_g, color_data[3*i+1]); EXPECT_EQ(*iter_const_1_b, *iter_const_2_b); EXPECT_EQ(*iter_const_1_b, color_data[3*i+2]); // This is to test the different operators ++iter_const_2_r; iter_const_2_g += 1; iter_const_2_b = iter_const_2_b + 1; } EXPECT_EQ(i, n_points); } int main(int argc, char** argv) { ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } ros-common-msgs-1.12.7/sensor_msgs/test/test_image_encodings.cpp000066400000000000000000000072731337176563300250700ustar00rootroot00000000000000/* * Software License Agreement (BSD License) * * Copyright (c) 2016, Kentaro Wada. * All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions * are met: * * * Redistributions of source code must retain the above copyright * notice, this list of conditions and the following disclaimer. * * Redistributions in binary form must reproduce the above * copyright notice, this list of conditions and the following * disclaimer in the documentation and/or other materials provided * with the distribution. * * Neither the name of Willow Garage, Inc. nor the names of its * contributors may be used to endorse or promote products derived * from this software without specific prior written permission. * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. */ #include #include TEST(sensor_msgs, NumChannels) { ASSERT_EQ(sensor_msgs::image_encodings::numChannels("mono8"), 1); ASSERT_EQ(sensor_msgs::image_encodings::numChannels("rgb8"), 3); ASSERT_EQ(sensor_msgs::image_encodings::numChannels("8UC"), 1); ASSERT_EQ(sensor_msgs::image_encodings::numChannels("8UC3"), 3); ASSERT_EQ(sensor_msgs::image_encodings::numChannels("8UC10"), 10); ASSERT_EQ(sensor_msgs::image_encodings::numChannels("16UC"), 1); ASSERT_EQ(sensor_msgs::image_encodings::numChannels("16UC3"), 3); ASSERT_EQ(sensor_msgs::image_encodings::numChannels("16UC10"), 10); ASSERT_EQ(sensor_msgs::image_encodings::numChannels("32SC"), 1); ASSERT_EQ(sensor_msgs::image_encodings::numChannels("32SC3"), 3); ASSERT_EQ(sensor_msgs::image_encodings::numChannels("32SC10"), 10); ASSERT_EQ(sensor_msgs::image_encodings::numChannels("64FC"), 1); ASSERT_EQ(sensor_msgs::image_encodings::numChannels("64FC3"), 3); ASSERT_EQ(sensor_msgs::image_encodings::numChannels("64FC10"), 10); } TEST(sensor_msgs, bitDepth) { ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("mono8"), 8); ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("rgb8"), 8); ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("8UC"), 8); ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("8UC3"), 8); ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("8UC10"), 8); ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("16UC"), 16); ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("16UC3"), 16); ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("16UC10"), 16); ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("32SC"), 32); ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("32SC3"), 32); ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("32SC10"), 32); ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("64FC"), 64); ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("64FC3"), 64); ASSERT_EQ(sensor_msgs::image_encodings::bitDepth("64FC10"), 64); } int main(int argc, char** argv) { ::testing::InitGoogleTest(&argc, argv); return RUN_ALL_TESTS(); } ros-common-msgs-1.12.7/shape_msgs/000077500000000000000000000000001337176563300170115ustar00rootroot00000000000000ros-common-msgs-1.12.7/shape_msgs/CHANGELOG.rst000066400000000000000000000061101337176563300210300ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package shape_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.12.7 (2018-11-06) ------------------- 1.12.6 (2018-05-03) ------------------- 1.12.5 (2016-09-30) ------------------- 1.12.4 (2016-02-22) ------------------- 1.12.3 (2015-04-20) ------------------- 1.12.2 (2015-03-21) ------------------- 1.12.1 (2015-03-17) ------------------- * updating outdated urls. fixes `#52 `_. * Contributors: Tully Foote 1.12.0 (2014-12-29) ------------------- 1.11.6 (2014-11-04) ------------------- 1.11.5 (2014-10-27) ------------------- 1.11.4 (2014-06-19) ------------------- 1.11.3 (2014-05-07) ------------------- * Export architecture_independent flag in package.xml * Contributors: Scott K Logan 1.11.2 (2014-04-24) ------------------- 1.11.1 (2014-04-16) ------------------- 1.11.0 (2014-03-04) ------------------- 1.10.6 (2014-02-27) ------------------- 1.10.5 (2014-02-25) ------------------- 1.10.4 (2014-02-18) ------------------- * Add a description to shape_msgs. * Contributors: Michael Ferguson 1.10.3 (2014-01-07) ------------------- 1.10.2 (2013-08-19) ------------------- 1.10.1 (2013-08-16) ------------------- 1.10.0 (2013-07-13) ------------------- 1.9.16 (2013-05-21) ------------------- 1.9.15 (2013-03-08) ------------------- 1.9.14 (2013-01-19) ------------------- 1.9.13 (2013-01-13) ------------------- 1.9.12 (2013-01-02) ------------------- 1.9.11 (2012-12-17) ------------------- * modified dep type of catkin 1.9.10 (2012-12-13) ------------------- * add missing downstream depend * switched from langs to message_* packages 1.9.9 (2012-11-22) ------------------ 1.9.8 (2012-11-14) ------------------ 1.9.7 (2012-10-30) ------------------ * fix catkin function order 1.9.6 (2012-10-18) ------------------ * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 1.9.5 (2012-09-28) ------------------ * fixed missing find genmsg 1.9.4 (2012-09-27 18:06) ------------------------ 1.9.3 (2012-09-27 17:39) ------------------------ * cleanup * updated to latest catkin * fixed dependencies and more * updated to latest catkin: created package.xmls, updated CmakeLists.txt 1.9.2 (2012-09-05) ------------------ * updated pkg-config in manifest.xml 1.9.1 (2012-09-04) ------------------ * use install destination variables, removed manual installation of manifests 1.9.0 (2012-08-29) ------------------ * updated to current catkin 1.8.13 (2012-07-26 18:34:15 +0000) ---------------------------------- * Add more comments, change the types to uint8 * updates to shape based on discussion with vincent (and dave h.) * removing un-needed stack.sml * updated deps * one more convention * more changes after talking to Dave * update per Tully's latest comments * more work on shapes, based on reviews * apply updates from Tully * removing C++ code from shapes_msgs * shange comment as Dave suggested 1.8.8 (2012-06-12 22:36) ------------------------ * update ID values so they resemble markers better * address Vincent's comments * applying Sachin's comments * add shape msgs ros-common-msgs-1.12.7/shape_msgs/CMakeLists.txt000066400000000000000000000005711337176563300215540ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(shape_msgs) find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation std_msgs) add_message_files( DIRECTORY msg FILES Mesh.msg MeshTriangle.msg Plane.msg SolidPrimitive.msg) generate_messages(DEPENDENCIES geometry_msgs std_msgs) catkin_package(CATKIN_DEPENDS geometry_msgs message_runtime std_msgs) ros-common-msgs-1.12.7/shape_msgs/msg/000077500000000000000000000000001337176563300175775ustar00rootroot00000000000000ros-common-msgs-1.12.7/shape_msgs/msg/Mesh.msg000066400000000000000000000003041337176563300212000ustar00rootroot00000000000000# Definition of a mesh # list of triangles; the index values refer to positions in vertices[] MeshTriangle[] triangles # the actual vertices that make up the mesh geometry_msgs/Point[] vertices ros-common-msgs-1.12.7/shape_msgs/msg/MeshTriangle.msg000066400000000000000000000000771337176563300226750ustar00rootroot00000000000000# Definition of a triangle's vertices uint32[3] vertex_indices ros-common-msgs-1.12.7/shape_msgs/msg/Plane.msg000066400000000000000000000002311337176563300213420ustar00rootroot00000000000000# Representation of a plane, using the plane equation ax + by + cz + d = 0 # a := coef[0] # b := coef[1] # c := coef[2] # d := coef[3] float64[4] coef ros-common-msgs-1.12.7/shape_msgs/msg/SolidPrimitive.msg000066400000000000000000000021621337176563300232530ustar00rootroot00000000000000# Define box, sphere, cylinder, cone # All shapes are defined to have their bounding boxes centered around 0,0,0. uint8 BOX=1 uint8 SPHERE=2 uint8 CYLINDER=3 uint8 CONE=4 # The type of the shape uint8 type # The dimensions of the shape float64[] dimensions # The meaning of the shape dimensions: each constant defines the index in the 'dimensions' array # For the BOX type, the X, Y, and Z dimensions are the length of the corresponding # sides of the box. uint8 BOX_X=0 uint8 BOX_Y=1 uint8 BOX_Z=2 # For the SPHERE type, only one component is used, and it gives the radius of # the sphere. uint8 SPHERE_RADIUS=0 # For the CYLINDER and CONE types, the center line is oriented along # the Z axis. Therefore the CYLINDER_HEIGHT (CONE_HEIGHT) component # of dimensions gives the height of the cylinder (cone). The # CYLINDER_RADIUS (CONE_RADIUS) component of dimensions gives the # radius of the base of the cylinder (cone). Cone and cylinder # primitives are defined to be circular. The tip of the cone is # pointing up, along +Z axis. uint8 CYLINDER_HEIGHT=0 uint8 CYLINDER_RADIUS=1 uint8 CONE_HEIGHT=0 uint8 CONE_RADIUS=1 ros-common-msgs-1.12.7/shape_msgs/package.xml000066400000000000000000000014131337176563300211250ustar00rootroot00000000000000 shape_msgs 1.12.7 This package contains messages for defining shapes, such as simple solid object primitives (cube, sphere, etc), planes, and meshes. Ioan Sucan BSD http://wiki.ros.org/shape_msgs Ioan Sucan catkin geometry_msgs message_generation std_msgs geometry_msgs message_runtime std_msgs ros-common-msgs-1.12.7/stereo_msgs/000077500000000000000000000000001337176563300172125ustar00rootroot00000000000000ros-common-msgs-1.12.7/stereo_msgs/CHANGELOG.rst000066400000000000000000000065161337176563300212430ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package stereo_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.12.7 (2018-11-06) ------------------- 1.12.6 (2018-05-03) ------------------- 1.12.5 (2016-09-30) ------------------- * Fix spelling mistakes * Contributors: trorornmn 1.12.4 (2016-02-22) ------------------- 1.12.3 (2015-04-20) ------------------- 1.12.2 (2015-03-21) ------------------- 1.12.1 (2015-03-17) ------------------- * updating outdated urls. fixes `#52 `_. * Contributors: Tully Foote 1.12.0 (2014-12-29) ------------------- 1.11.6 (2014-11-04) ------------------- 1.11.5 (2014-10-27) ------------------- 1.11.4 (2014-06-19) ------------------- 1.11.3 (2014-05-07) ------------------- * Export architecture_independent flag in package.xml * Contributors: Scott K Logan 1.11.2 (2014-04-24) ------------------- 1.11.1 (2014-04-16) ------------------- 1.11.0 (2014-03-04) ------------------- 1.10.6 (2014-02-27) ------------------- 1.10.5 (2014-02-25) ------------------- 1.10.4 (2014-02-18) ------------------- 1.10.3 (2014-01-07) ------------------- 1.10.2 (2013-08-19) ------------------- 1.10.1 (2013-08-16) ------------------- 1.10.0 (2013-07-13) ------------------- 1.9.16 (2013-05-21) ------------------- * update email in package.xml 1.9.15 (2013-03-08) ------------------- 1.9.14 (2013-01-19) ------------------- 1.9.13 (2013-01-13) ------------------- 1.9.12 (2013-01-02) ------------------- 1.9.11 (2012-12-17) ------------------- * modified dep type of catkin 1.9.10 (2012-12-13) ------------------- * add missing downstream depend * switched from langs to message_* packages 1.9.9 (2012-11-22) ------------------ 1.9.8 (2012-11-14) ------------------ 1.9.7 (2012-10-30) ------------------ * fix catkin function order 1.9.6 (2012-10-18) ------------------ * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 1.9.5 (2012-09-28) ------------------ * fixed missing find genmsg 1.9.4 (2012-09-27 18:06) ------------------------ 1.9.3 (2012-09-27 17:39) ------------------------ * cleanup * updated to latest catkin * fixed dependencies and more * updated to latest catkin: created package.xmls, updated CmakeLists.txt 1.9.2 (2012-09-05) ------------------ * updated pkg-config in manifest.xml 1.9.1 (2012-09-04) ------------------ * use install destination variables, removed manual installation of manifests 1.9.0 (2012-08-29) ------------------ 1.8.13 (2012-07-26 18:34:15 +0000) ---------------------------------- 1.8.8 (2012-06-12 22:36) ------------------------ * removed obsolete catkin tag from manifest files * fixed package dependencies for several common messages (fixed `#3956 `_) * adding manifest exports * removed depend, added catkin * 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 * common_msgs: removing migration rules as all are over a year old * bye bye vestigial MSG_DIRS * stereo_msgs: catkin'd * adios rosbuild2 in manifest.xml * missing dependencies * updating bagmigration exports * rosbuild2 taking shape * removing old exports for msg/cpp and reving to 1.3.7 in preparation for release * stereo_msgs into common_msgs `#4637 `_ ros-common-msgs-1.12.7/stereo_msgs/CMakeLists.txt000066400000000000000000000005121337176563300217500ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(stereo_msgs) find_package(catkin REQUIRED COMPONENTS sensor_msgs message_generation std_msgs) add_message_files( DIRECTORY msg FILES DisparityImage.msg) generate_messages(DEPENDENCIES sensor_msgs std_msgs) catkin_package(CATKIN_DEPENDS message_runtime sensor_msgs std_msgs) ros-common-msgs-1.12.7/stereo_msgs/mainpage.dox000066400000000000000000000001651337176563300215110ustar00rootroot00000000000000/** \mainpage \htmlinclude manifest.html \b stereo_msgs contains messages for representing stereo-related data. */ ros-common-msgs-1.12.7/stereo_msgs/msg/000077500000000000000000000000001337176563300200005ustar00rootroot00000000000000ros-common-msgs-1.12.7/stereo_msgs/msg/DisparityImage.msg000066400000000000000000000021611337176563300234230ustar00rootroot00000000000000# Separate header for compatibility with current TimeSynchronizer. # Likely to be removed in a later release, use image.header instead. Header header # Floating point disparity image. The disparities are pre-adjusted for any # x-offset between the principal points of the two cameras (in the case # that they are verged). That is: d = x_l - x_r - (cx_l - cx_r) sensor_msgs/Image image # Stereo geometry. For disparity d, the depth from the camera is Z = fT/d. float32 f # Focal length, pixels float32 T # Baseline, world units # Subwindow of (potentially) valid disparity values. sensor_msgs/RegionOfInterest valid_window # The range of disparities searched. # In the disparity image, any disparity less than min_disparity is invalid. # The disparity search range defines the horopter, or 3D volume that the # stereo algorithm can "see". Points with Z outside of: # Z_min = fT / max_disparity # Z_max = fT / min_disparity # could not be found. float32 min_disparity float32 max_disparity # Smallest allowed disparity increment. The smallest achievable depth range # resolution is delta_Z = (Z^2/fT)*delta_d. float32 delta_d ros-common-msgs-1.12.7/stereo_msgs/package.xml000066400000000000000000000014001337176563300213220ustar00rootroot00000000000000 stereo_msgs 1.12.7 stereo_msgs contains messages specific to stereo processing, such as disparity images. Tully Foote BSD http://wiki.ros.org/stereo_msgs Patrick Mihelich Kurt Konolige catkin message_generation sensor_msgs std_msgs message_runtime sensor_msgs std_msgs ros-common-msgs-1.12.7/trajectory_msgs/000077500000000000000000000000001337176563300200775ustar00rootroot00000000000000ros-common-msgs-1.12.7/trajectory_msgs/CHANGELOG.rst000066400000000000000000000066471337176563300221350ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package trajectory_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.12.7 (2018-11-06) ------------------- 1.12.6 (2018-05-03) ------------------- 1.12.5 (2016-09-30) ------------------- * Fix spelling mistakes * Contributors: trorornmn 1.12.4 (2016-02-22) ------------------- 1.12.3 (2015-04-20) ------------------- 1.12.2 (2015-03-21) ------------------- 1.12.1 (2015-03-17) ------------------- * updating outdated urls. fixes `#52 `_. * Contributors: Tully Foote 1.12.0 (2014-12-29) ------------------- 1.11.6 (2014-11-04) ------------------- 1.11.5 (2014-10-27) ------------------- 1.11.4 (2014-06-19) ------------------- 1.11.3 (2014-05-07) ------------------- * Export architecture_independent flag in package.xml * Contributors: Scott K Logan 1.11.2 (2014-04-24) ------------------- 1.11.1 (2014-04-16) ------------------- 1.11.0 (2014-03-04) ------------------- 1.10.6 (2014-02-27) ------------------- 1.10.5 (2014-02-25) ------------------- 1.10.4 (2014-02-18) ------------------- * make link to control messages a real link * Add a description to trajectory_msgs * Contributors: Michael Ferguson 1.10.3 (2014-01-07) ------------------- 1.10.2 (2013-08-19) ------------------- 1.10.1 (2013-08-16) ------------------- * add effort for JointTrajectoryPoint `#13 ` * fixing maintainer * updating maintainer 1.10.0 (2013-07-13) ------------------- * add MultiDOFJointTrajectory 1.9.16 (2013-05-21) ------------------- 1.9.15 (2013-03-08) ------------------- 1.9.14 (2013-01-19) ------------------- 1.9.13 (2013-01-13) ------------------- 1.9.12 (2013-01-02) ------------------- 1.9.11 (2012-12-17) ------------------- * modified dep type of catkin 1.9.10 (2012-12-13) ------------------- * add missing downstream depend * switched from langs to message_* packages 1.9.9 (2012-11-22) ------------------ 1.9.8 (2012-11-14) ------------------ 1.9.7 (2012-10-30) ------------------ * fix catkin function order 1.9.6 (2012-10-18) ------------------ * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 1.9.5 (2012-09-28) ------------------ * fixed missing find genmsg 1.9.4 (2012-09-27 18:06) ------------------------ 1.9.3 (2012-09-27 17:39) ------------------------ * cleanup * updated to latest catkin * fixed dependencies and more * updated to latest catkin: created package.xmls, updated CmakeLists.txt 1.9.2 (2012-09-05) ------------------ * updated pkg-config in manifest.xml 1.9.1 (2012-09-04) ------------------ * use install destination variables, removed manual installation of manifests 1.9.0 (2012-08-29) ------------------ 1.8.13 (2012-07-26 18:34:15 +0000) ---------------------------------- 1.8.8 (2012-06-12 22:36) ------------------------ * removed obsolete catkin tag from manifest files * add missing packages * adding manifest exports * removed depend, added catkin * 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 * trajectory_msgs: catkin'd * common_msgs: starting catkin conversion * adios rosbuild2 in manifest.xml * rosbuild2 taking shape * removing old exports for msg/cpp and reving to 1.3.7 in preparation for release * migrating trajectory_msgs to common_msgs from pr2_controllers `#4675 `_ ros-common-msgs-1.12.7/trajectory_msgs/CMakeLists.txt000066400000000000000000000010001337176563300226260ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(trajectory_msgs) find_package(catkin REQUIRED COMPONENTS message_generation std_msgs geometry_msgs) add_message_files( DIRECTORY msg FILES JointTrajectory.msg JointTrajectoryPoint.msg MultiDOFJointTrajectory.msg MultiDOFJointTrajectoryPoint.msg ) generate_messages(DEPENDENCIES std_msgs geometry_msgs) catkin_package(CATKIN_DEPENDS message_runtime std_msgs geometry_msgs) install(DIRECTORY rules DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) ros-common-msgs-1.12.7/trajectory_msgs/msg/000077500000000000000000000000001337176563300206655ustar00rootroot00000000000000ros-common-msgs-1.12.7/trajectory_msgs/msg/JointTrajectory.msg000066400000000000000000000001001337176563300245160ustar00rootroot00000000000000Header header string[] joint_names JointTrajectoryPoint[] pointsros-common-msgs-1.12.7/trajectory_msgs/msg/JointTrajectoryPoint.msg000066400000000000000000000005211337176563300255370ustar00rootroot00000000000000# Each trajectory point specifies either positions[, velocities[, accelerations]] # or positions[, effort] for the trajectory to be executed. # All specified values are in the same order as the joint names in JointTrajectory.msg float64[] positions float64[] velocities float64[] accelerations float64[] effort duration time_from_start ros-common-msgs-1.12.7/trajectory_msgs/msg/MultiDOFJointTrajectory.msg000066400000000000000000000007341337176563300260770ustar00rootroot00000000000000# The header is used to specify the coordinate frame and the reference time for the trajectory durations Header header # A representation of a multi-dof joint trajectory (each point is a transformation) # Each point along the trajectory will include an array of positions/velocities/accelerations # that has the same length as the array of joint names, and has the same order of joints as # the joint names array. string[] joint_names MultiDOFJointTrajectoryPoint[] points ros-common-msgs-1.12.7/trajectory_msgs/msg/MultiDOFJointTrajectoryPoint.msg000066400000000000000000000005121337176563300271030ustar00rootroot00000000000000# Each multi-dof joint can specify a transform (up to 6 DOF) geometry_msgs/Transform[] transforms # There can be a velocity specified for the origin of the joint geometry_msgs/Twist[] velocities # There can be an acceleration specified for the origin of the joint geometry_msgs/Twist[] accelerations duration time_from_start ros-common-msgs-1.12.7/trajectory_msgs/package.xml000066400000000000000000000017531337176563300222220ustar00rootroot00000000000000 trajectory_msgs 1.12.7 This package defines messages for defining robot trajectories. These messages are also the building blocks of most of the control_msgs actions. Tully Foote BSD http://wiki.ros.org/trajectory_msgs Stuart Glaser catkin message_generation geometry_msgs std_msgs message_runtime geometry_msgs std_msgs rosbag_migration_rule ros-common-msgs-1.12.7/trajectory_msgs/rules/000077500000000000000000000000001337176563300212315ustar00rootroot00000000000000ros-common-msgs-1.12.7/trajectory_msgs/rules/JointTrajectoryPoint_Groovy2Hydro_08.10.2013.bmr000066400000000000000000000017661337176563300316600ustar00rootroot00000000000000class update_trajectory_msgs_JointTrajectoryPoint_84fd2dcf68773c3dc0e9db894f4e8b40(MessageUpdateRule): old_type = "trajectory_msgs/JointTrajectoryPoint" old_full_text = """ float64[] positions float64[] velocities float64[] accelerations duration time_from_start """ new_type = "trajectory_msgs/JointTrajectoryPoint" new_full_text = """ # Each trajectory point specifies either positions[, velocities[, accelerations]] # or positions[, effort] for the trajectory to be executed. # All specified values are in the same order as the joint names in JointTrajectory.msg float64[] positions float64[] velocities float64[] accelerations float64[] effort duration time_from_start """ order = 0 migrated_types = [] valid = True def update(self, old_msg, new_msg): new_msg.positions = old_msg.positions new_msg.velocities = old_msg.velocities new_msg.accelerations = old_msg.accelerations #No matching field name in old message new_msg.effort = [] new_msg.time_from_start = old_msg.time_from_start ros-common-msgs-1.12.7/visualization_msgs/000077500000000000000000000000001337176563300206125ustar00rootroot00000000000000ros-common-msgs-1.12.7/visualization_msgs/CHANGELOG.rst000066400000000000000000000135161337176563300226410ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package visualization_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 1.12.7 (2018-11-06) ------------------- 1.12.6 (2018-05-03) ------------------- 1.12.5 (2016-09-30) ------------------- * Fix spelling mistakes * Contributors: trorornmn 1.12.4 (2016-02-22) ------------------- 1.12.3 (2015-04-20) ------------------- 1.12.2 (2015-03-21) ------------------- 1.12.1 (2015-03-17) ------------------- 1.12.0 (2014-12-29) ------------------- * Enable DELETEALL=3 definition for marker action. Fixes `#39 `_ * Contributors: Tully Foote 1.11.6 (2014-11-04) ------------------- 1.11.5 (2014-10-27) ------------------- 1.11.4 (2014-06-19) ------------------- * Added comment to document new Rviz Marker action * Contributors: Dave Coleman 1.11.3 (2014-05-07) ------------------- * Export architecture_independent flag in package.xml * Contributors: Scott K Logan 1.11.2 (2014-04-24) ------------------- 1.11.1 (2014-04-16) ------------------- 1.11.0 (2014-03-04) ------------------- 1.10.6 (2014-02-27) ------------------- 1.10.5 (2014-02-25) ------------------- 1.10.4 (2014-02-18) ------------------- 1.10.3 (2014-01-07) ------------------- 1.10.2 (2013-08-19) ------------------- 1.10.1 (2013-08-16) ------------------- 1.10.0 (2013-07-13) ------------------- 1.9.16 (2013-05-21) ------------------- * change comment to indicate 3D control modes can now be used with mouse. * update email in package.xml 1.9.15 (2013-03-08) ------------------- 1.9.14 (2013-01-19) ------------------- 1.9.13 (2013-01-13) ------------------- 1.9.12 (2013-01-02) ------------------- 1.9.11 (2012-12-17) ------------------- * modified dep type of catkin 1.9.10 (2012-12-13) ------------------- * add missing downstream depend * switched from langs to message_* packages 1.9.9 (2012-11-22) ------------------ 1.9.8 (2012-11-14) ------------------ 1.9.7 (2012-10-30) ------------------ * fix catkin function order 1.9.6 (2012-10-18) ------------------ * Adds 3D control modes to interactive marker msgs * updated cmake min version to 2.8.3, use cmake_parse_arguments instead of custom macro 1.9.5 (2012-09-28) ------------------ * fixed missing find genmsg 1.9.4 (2012-09-27 18:06) ------------------------ 1.9.3 (2012-09-27 17:39) ------------------------ * cleanup * updated to latest catkin * fixed dependencies and more * updated to latest catkin: created package.xmls, updated CmakeLists.txt 1.9.2 (2012-09-05) ------------------ * updated pkg-config in manifest.xml 1.9.1 (2012-09-04) ------------------ * use install destination variables, removed manual installation of manifests 1.9.0 (2012-08-29) ------------------ 1.8.13 (2012-07-26 18:34:15 +0000) ---------------------------------- 1.8.8 (2012-06-12 22:36) ------------------------ * removed obsolete catkin tag from manifest files * fixed package dependency for another common message (`#3956 `_), removed unnecessary package name from another message * fixed package dependencies for several common messages (fixed `#3956 `_) * adding manifest exports * removed depend, added catkin * 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 * common_msgs: removing migration rules as all are over a year old * bye bye vestigial MSG_DIRS * visualization_msgs: catkin'd * adios rosbuild2 in manifest.xml * visualization_msgs: added 3D point of mouse event to InteractiveMarkerFeedback; fixed typo in comment in InteractiveMarkerControl. * visualization_msgs: moved INIT function of InteractiveMarkerUpdate.msg into its own message: InteractiveMarkerInit.msg, in accordance with bug `#5021 `_ * visualization_msgs: updated InteractiveMarker, MenuEntry, and InteractiveMarkerFeedback messages and removed Menu message per API review decision about cleaning up menu specifications * visualization_msgs: switched byte fields to uint8 per API review * visualization_msgs: clarified comment per API review * visualization_msgs: moved header to be first field of InteractiveMarkerFeedback per API review. * visualization_msgs: comments clarified per API review. * visualization_msgs: changed KEEP_ALIVE constant values in different messages to use the same value. * - added mouse_down / mouse_up events * changed layout of Menu messages * updated documentation * - added server_id, client_id; keep-alive and init updates; removed frame_locked option (now: timestamp=0) * added header to i.m. feedback * removed reference_frame again * added reference_frame_id to i.m. * updated docum., added descripion field to interactive marker, changed tool_tip to description in i.m. control * updated feedback ducomentation * PING->KEEP_ALIVE * added PING feedback type * added independent_marker_orientation to msg/InteractiveMarkerControl.msg * updated interactive marker messages * cleaned up the mess of commit `#36835 `_ * rosbuild2 updates * renamed InteractiveMarkerArray to InteractiveMarkerUpdate * updated msg/InteractiveMarkerFeedback.msg * updated interactive marker spec * updated documentation, namiing of fields for interactive ** * removed cpp interface from visualization_msgs again. too much work, too little outcome * made a better cpp interface for interactive marker generation * added view facing markers spec * added more functions to include/visualization_msgs/interactive_marker_tools.h * added initial version of interactive marker messages * rosbuild2 taking shape * removing old exports for msg/cpp and reving to 1.3.7 in preparation for release * update rosbagmigration dependency (`#4510 `_) * add visualization_msgs to common_msgs ros-common-msgs-1.12.7/visualization_msgs/CMakeLists.txt000066400000000000000000000010611337176563300233500ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(visualization_msgs) find_package(catkin REQUIRED COMPONENTS geometry_msgs message_generation std_msgs) add_message_files( DIRECTORY msg FILES ImageMarker.msg InteractiveMarker.msg InteractiveMarkerControl.msg InteractiveMarkerFeedback.msg InteractiveMarkerInit.msg InteractiveMarkerPose.msg InteractiveMarkerUpdate.msg MarkerArray.msg Marker.msg MenuEntry.msg ) generate_messages(DEPENDENCIES geometry_msgs std_msgs) catkin_package(CATKIN_DEPENDS geometry_msgs message_runtime std_msgs) ros-common-msgs-1.12.7/visualization_msgs/mainpage.dox000066400000000000000000000005171337176563300231120ustar00rootroot00000000000000/** \mainpage \htmlinclude manifest.html \b visualization_msgs is a package to collect all visualization-related messages into one place. The messages it currently contains are: - \ref visualization_msgs::Marker - \ref visualization_msgs::MarkerArray - \ref visualization_msgs::ImageMarker - \ref visualization_msgs::Polyline */ros-common-msgs-1.12.7/visualization_msgs/msg/000077500000000000000000000000001337176563300214005ustar00rootroot00000000000000ros-common-msgs-1.12.7/visualization_msgs/msg/ImageMarker.msg000066400000000000000000000014731337176563300243010ustar00rootroot00000000000000uint8 CIRCLE=0 uint8 LINE_STRIP=1 uint8 LINE_LIST=2 uint8 POLYGON=3 uint8 POINTS=4 uint8 ADD=0 uint8 REMOVE=1 Header header string ns # namespace, used with id to form a unique id int32 id # unique id within the namespace int32 type # CIRCLE/LINE_STRIP/etc. int32 action # ADD/REMOVE geometry_msgs/Point position # 2D, in pixel-coords float32 scale # the diameter for a circle, etc. std_msgs/ColorRGBA outline_color uint8 filled # whether to fill in the shape with color std_msgs/ColorRGBA fill_color # color [0.0-1.0] duration lifetime # How long the object should last before being automatically deleted. 0 means forever geometry_msgs/Point[] points # used for LINE_STRIP/LINE_LIST/POINTS/etc., 2D in pixel coords std_msgs/ColorRGBA[] outline_colors # a color for each line, point, etc.ros-common-msgs-1.12.7/visualization_msgs/msg/InteractiveMarker.msg000066400000000000000000000014501337176563300255270ustar00rootroot00000000000000# Time/frame info. # If header.time is set to 0, the marker will be retransformed into # its frame on each timestep. You will receive the pose feedback # in the same frame. # Otherwise, you might receive feedback in a different frame. # For rviz, this will be the current 'fixed frame' set by the user. Header header # Initial pose. Also, defines the pivot point for rotations. geometry_msgs/Pose pose # Identifying string. Must be globally unique in # the topic that this message is sent through. string name # Short description (< 40 characters). string description # Scale to be used for default controls (default=1). float32 scale # All menu and submenu entries associated with this marker. MenuEntry[] menu_entries # List of controls displayed for this marker. InteractiveMarkerControl[] controls ros-common-msgs-1.12.7/visualization_msgs/msg/InteractiveMarkerControl.msg000066400000000000000000000050321337176563300270700ustar00rootroot00000000000000# Represents a control that is to be displayed together with an interactive marker # Identifying string for this control. # You need to assign a unique value to this to receive feedback from the GUI # on what actions the user performs on this control (e.g. a button click). string name # Defines the local coordinate frame (relative to the pose of the parent # interactive marker) in which is being rotated and translated. # Default: Identity geometry_msgs/Quaternion orientation # Orientation mode: controls how orientation changes. # INHERIT: Follow orientation of interactive marker # FIXED: Keep orientation fixed at initial state # VIEW_FACING: Align y-z plane with screen (x: forward, y:left, z:up). uint8 INHERIT = 0 uint8 FIXED = 1 uint8 VIEW_FACING = 2 uint8 orientation_mode # Interaction mode for this control # # NONE: This control is only meant for visualization; no context menu. # MENU: Like NONE, but right-click menu is active. # BUTTON: Element can be left-clicked. # MOVE_AXIS: Translate along local x-axis. # MOVE_PLANE: Translate in local y-z plane. # ROTATE_AXIS: Rotate around local x-axis. # MOVE_ROTATE: Combines MOVE_PLANE and ROTATE_AXIS. uint8 NONE = 0 uint8 MENU = 1 uint8 BUTTON = 2 uint8 MOVE_AXIS = 3 uint8 MOVE_PLANE = 4 uint8 ROTATE_AXIS = 5 uint8 MOVE_ROTATE = 6 # "3D" interaction modes work with the mouse+SHIFT+CTRL or with 3D cursors. # MOVE_3D: Translate freely in 3D space. # ROTATE_3D: Rotate freely in 3D space about the origin of parent frame. # MOVE_ROTATE_3D: Full 6-DOF freedom of translation and rotation about the cursor origin. uint8 MOVE_3D = 7 uint8 ROTATE_3D = 8 uint8 MOVE_ROTATE_3D = 9 uint8 interaction_mode # If true, the contained markers will also be visible # when the gui is not in interactive mode. bool always_visible # Markers to be displayed as custom visual representation. # Leave this empty to use the default control handles. # # Note: # - The markers can be defined in an arbitrary coordinate frame, # but will be transformed into the local frame of the interactive marker. # - If the header of a marker is empty, its pose will be interpreted as # relative to the pose of the parent interactive marker. Marker[] markers # In VIEW_FACING mode, set this to true if you don't want the markers # to be aligned with the camera view point. The markers will show up # as in INHERIT mode. bool independent_marker_orientation # Short description (< 40 characters) of what this control does, # e.g. "Move the robot". # Default: A generic description based on the interaction mode string description ros-common-msgs-1.12.7/visualization_msgs/msg/InteractiveMarkerFeedback.msg000066400000000000000000000023501337176563300271340ustar00rootroot00000000000000# Time/frame info. Header header # Identifying string. Must be unique in the topic namespace. string client_id # Feedback message sent back from the GUI, e.g. # when the status of an interactive marker was modified by the user. # Specifies which interactive marker and control this message refers to string marker_name string control_name # Type of the event # KEEP_ALIVE: sent while dragging to keep up control of the marker # MENU_SELECT: a menu entry has been selected # BUTTON_CLICK: a button control has been clicked # POSE_UPDATE: the pose has been changed using one of the controls uint8 KEEP_ALIVE = 0 uint8 POSE_UPDATE = 1 uint8 MENU_SELECT = 2 uint8 BUTTON_CLICK = 3 uint8 MOUSE_DOWN = 4 uint8 MOUSE_UP = 5 uint8 event_type # Current pose of the marker # Note: Has to be valid for all feedback types. geometry_msgs/Pose pose # Contains the ID of the selected menu entry # Only valid for MENU_SELECT events. uint32 menu_entry_id # If event_type is BUTTON_CLICK, MOUSE_DOWN, or MOUSE_UP, mouse_point # may contain the 3 dimensional position of the event on the # control. If it does, mouse_point_valid will be true. mouse_point # will be relative to the frame listed in the header. geometry_msgs/Point mouse_point bool mouse_point_valid ros-common-msgs-1.12.7/visualization_msgs/msg/InteractiveMarkerInit.msg000066400000000000000000000007331337176563300263560ustar00rootroot00000000000000# Identifying string. Must be unique in the topic namespace # that this server works on. string server_id # Sequence number. # The client will use this to detect if it has missed a subsequent # update. Every update message will have the same sequence number as # an init message. Clients will likely want to unsubscribe from the # init topic after a successful initialization to avoid receiving # duplicate data. uint64 seq_num # All markers. InteractiveMarker[] markers ros-common-msgs-1.12.7/visualization_msgs/msg/InteractiveMarkerPose.msg000066400000000000000000000003441337176563300263570ustar00rootroot00000000000000# Time/frame info. Header header # Initial pose. Also, defines the pivot point for rotations. geometry_msgs/Pose pose # Identifying string. Must be globally unique in # the topic that this message is sent through. string name ros-common-msgs-1.12.7/visualization_msgs/msg/InteractiveMarkerUpdate.msg000066400000000000000000000016661337176563300267030ustar00rootroot00000000000000# Identifying string. Must be unique in the topic namespace # that this server works on. string server_id # Sequence number. # The client will use this to detect if it has missed an update. uint64 seq_num # Type holds the purpose of this message. It must be one of UPDATE or KEEP_ALIVE. # UPDATE: Incremental update to previous state. # The sequence number must be 1 higher than for # the previous update. # KEEP_ALIVE: Indicates the that the server is still living. # The sequence number does not increase. # No payload data should be filled out (markers, poses, or erases). uint8 KEEP_ALIVE = 0 uint8 UPDATE = 1 uint8 type #Note: No guarantees on the order of processing. # Contents must be kept consistent by sender. #Markers to be added or updated InteractiveMarker[] markers #Poses of markers that should be moved InteractiveMarkerPose[] poses #Names of markers to be erased string[] erases ros-common-msgs-1.12.7/visualization_msgs/msg/Marker.msg000066400000000000000000000036171337176563300233400ustar00rootroot00000000000000# 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 uint8 ARROW=0 uint8 CUBE=1 uint8 SPHERE=2 uint8 CYLINDER=3 uint8 LINE_STRIP=4 uint8 LINE_LIST=5 uint8 CUBE_LIST=6 uint8 SPHERE_LIST=7 uint8 POINTS=8 uint8 TEXT_VIEW_FACING=9 uint8 MESH_RESOURCE=10 uint8 TRIANGLE_LIST=11 uint8 ADD=0 uint8 MODIFY=0 uint8 DELETE=2 uint8 DELETEALL=3 Header header # header for time/frame information string ns # Namespace to place this object in... used in conjunction with id to create a unique name for the object int32 id # object ID useful in conjunction with the namespace for manipulating and deleting the object later int32 type # Type of object int32 action # 0 add/modify an object, 1 (deprecated), 2 deletes an object, 3 deletes all objects geometry_msgs/Pose pose # Pose of the object geometry_msgs/Vector3 scale # Scale of the object 1,1,1 means default (usually 1 meter square) std_msgs/ColorRGBA color # Color [0.0-1.0] duration lifetime # How long the object should last before being automatically deleted. 0 means forever bool frame_locked # If this marker should be frame-locked, i.e. retransformed into its frame every timestep #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) geometry_msgs/Point[] points #Only used if the type specified has some use for them (eg. POINTS, LINE_STRIP, ...) #number of colors must either be 0 or equal to the number of points #NOTE: alpha is not yet used std_msgs/ColorRGBA[] colors # NOTE: only used for text markers string text # NOTE: only used for MESH_RESOURCE markers string mesh_resource bool mesh_use_embedded_materials ros-common-msgs-1.12.7/visualization_msgs/msg/MarkerArray.msg000066400000000000000000000000211337176563300243210ustar00rootroot00000000000000Marker[] markers ros-common-msgs-1.12.7/visualization_msgs/msg/MenuEntry.msg000066400000000000000000000030621337176563300240370ustar00rootroot00000000000000# MenuEntry message. # Each InteractiveMarker message has an array of MenuEntry messages. # A collection of MenuEntries together describe a # menu/submenu/subsubmenu/etc tree, though they are stored in a flat # array. The tree structure is represented by giving each menu entry # an ID number and a "parent_id" field. Top-level entries are the # ones with parent_id = 0. Menu entries are ordered within their # level the same way they are ordered in the containing array. Parent # entries must appear before their children. # Example: # - id = 3 # parent_id = 0 # title = "fun" # - id = 2 # parent_id = 0 # title = "robot" # - id = 4 # parent_id = 2 # title = "pr2" # - id = 5 # parent_id = 2 # title = "turtle" # # Gives a menu tree like this: # - fun # - robot # - pr2 # - turtle # ID is a number for each menu entry. Must be unique within the # control, and should never be 0. uint32 id # ID of the parent of this menu entry, if it is a submenu. If this # menu entry is a top-level entry, set parent_id to 0. uint32 parent_id # menu / entry title string title # Arguments to command indicated by command_type (below) string command # Command_type stores the type of response desired when this menu # entry is clicked. # FEEDBACK: send an InteractiveMarkerFeedback message with menu_entry_id set to this entry's id. # ROSRUN: execute "rosrun" with arguments given in the command field (above). # ROSLAUNCH: execute "roslaunch" with arguments given in the command field (above). uint8 FEEDBACK=0 uint8 ROSRUN=1 uint8 ROSLAUNCH=2 uint8 command_type ros-common-msgs-1.12.7/visualization_msgs/package.xml000066400000000000000000000024311337176563300227270ustar00rootroot00000000000000 visualization_msgs 1.12.7 visualization_msgs is a set of messages used by higher level packages, such as rviz, that deal in visualization-specific data. The main messages in visualization_msgs is visualization_msgs/Marker. The marker message is used to send visualization "markers" such as boxes, spheres, arrows, lines, etc. to a visualization environment such as rviz. See the rviz tutorial rviz tutorials for more information. Tully Foote BSD http://ros.org/wiki/visualization_msgs Josh Faust Davis Gossow catkin geometry_msgs message_generation std_msgs geometry_msgs message_runtime std_msgs