├── .travis.yml ├── CHANGELOG.rst ├── CMakeLists.txt ├── README.md ├── config └── example.yaml ├── include └── rosparam_shortcuts │ ├── deprecation.h │ └── rosparam_shortcuts.h ├── launch └── example.launch ├── package.xml └── src ├── example.cpp └── rosparam_shortcuts.cpp /.travis.yml: -------------------------------------------------------------------------------- 1 | # while this doesn't require sudo we don't want to run within a Docker container 2 | sudo: true 3 | dist: trusty 4 | language: python 5 | python: 6 | - "3.4" 7 | env: 8 | global: 9 | - JOB_PATH=/tmp/devel_job 10 | matrix: 11 | - ROS_DISTRO_NAME=kinetic OS_NAME=ubuntu OS_CODE_NAME=xenial ARCH=amd64 12 | - ROS_DISTRO_NAME=melodic OS_NAME=ubuntu OS_CODE_NAME=bionic ARCH=amd64 13 | install: 14 | # either install the latest released version of ros_buildfarm 15 | - pip install ros_buildfarm 16 | # checkout catkin for catkin_test_results script 17 | - git clone https://github.com/ros/catkin /tmp/catkin 18 | # run devel job for a ROS repository with the same name as this repo 19 | - export REPOSITORY_NAME=`basename $TRAVIS_BUILD_DIR` 20 | # use the code already checked out by Travis 21 | - mkdir -p $JOB_PATH/ws/src 22 | - cp -R $TRAVIS_BUILD_DIR $JOB_PATH/ws/src/ 23 | # generate the script to run a devel job for that target and repo 24 | - generate_devel_script.py https://raw.githubusercontent.com/ros-infrastructure/ros_buildfarm_config/production/index.yaml $ROS_DISTRO_NAME default $REPOSITORY_NAME $OS_NAME $OS_CODE_NAME $ARCH > $JOB_PATH/devel_job.sh 25 | - cd $JOB_PATH 26 | - cat devel_job.sh 27 | # run the actual job which involves Docker 28 | - sh devel_job.sh -y 29 | script: 30 | # get summary of test results 31 | - /tmp/catkin/bin/catkin_test_results $JOB_PATH/ws/test_results --all 32 | notifications: 33 | email: davetcoleman@gmail.com 34 | -------------------------------------------------------------------------------- /CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package rosparam_shortcuts 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.3.3 (2019-09-24) 6 | ------------------ 7 | * Switch run_depend to eigen_conversions. (`#12 `_) 8 | Eigen is header-only (so no run_depend needed), but eigen_conversions 9 | has a library that needs to be pulled in at runtime. 10 | Signed-off-by: Chris Lalancette 11 | * Contributors: Chris Lalancette 12 | 13 | 0.3.2 (2019-09-18) 14 | ------------------ 15 | * Update to new ros_buildfarm workspace directory 16 | * Add get() for geometry_msgs::Pose 17 | * Contributors: Henning Kayser 18 | 19 | 0.3.1 (2019-04-12) 20 | ------------------ 21 | * removing deprecated functions because catkin can't tell the difference between affine3d and isometry3d (`#9 `_) 22 | * Travis badge fixup (`#8 `_) 23 | * fixing travis and build tags 24 | * updating install instructions 25 | * adding melodic ci 26 | * Contributors: Mike Lautman 27 | 28 | 0.3.0 (2019-04-10) 29 | ------------------ 30 | * Deprecate Affine3d transforms and support Isometry3d (`#7 `_) 31 | * Merge pull request `#4 `_ from PickNikRobotics/kinetic-devel-eigen-additions 32 | adding support for loading trajectories and loading quaternions 33 | * removing EigenSTL 34 | * adding support for loading trajectories and loading quaternions 35 | * Merge pull request `#3 `_ from gavanderhoorn/patch-1 36 | Fix minor typo in API doc link. 37 | * Fix minor typo in API doc link. 38 | * Contributors: Dave Coleman, G.A. vd. Hoorn, Henning Kayser, mike 39 | 40 | 0.2.1 (2016-09-28) 41 | ------------------ 42 | * Fix Eigen3 include 43 | * Fix C++11 compiling method 44 | * Update Travis for Kinetic 45 | * Updated README 46 | * Contributors: Dave Coleman 47 | 48 | 0.2.0 (2016-06-29) 49 | ------------------ 50 | * Upgrade to Eigen3 per ROS Kinetic requirements 51 | * Converted to C++11 for ROS Kinetic 52 | * Removed deprecated functions 53 | * Improve documentation 54 | * fix typo 55 | * Added loading a vector to example 56 | * Contributors: Dave Coleman, Sammy Pfeiffer 57 | 58 | 0.1.1 (2015-12-18) 59 | ------------------ 60 | * Fixed CMake build 61 | * Ran roslint 62 | * Ran catkin lint 63 | * Updated example 64 | * Contributors: Dave Coleman 65 | 66 | 0.1.0 (2015-12-17) 67 | ------------------ 68 | * Deprecated long named functions in favor of short named functions 69 | * Removed redundant unsigned int function 70 | * Contributors: Dave Coleman 71 | 72 | 0.0.7 (2015-12-13) 73 | ------------------ 74 | * Added shortcut version of functions 75 | * Fix install 76 | * Contributors: Dave Coleman 77 | 78 | 0.0.6 (2015-12-10) 79 | ------------------ 80 | * Added example code 81 | * Contributors: Dave Coleman 82 | 83 | 0.0.5 (2015-12-09) 84 | ------------------ 85 | * Attempting to fix Eigen 86 | * Fix missing dependency 87 | * Contributors: Dave Coleman 88 | 89 | 0.0.4 (2015-12-07) 90 | ------------------ 91 | * Attempt to fix Eigen include dir 92 | * Contributors: Dave Coleman 93 | 94 | 0.0.3 (2015-12-05) 95 | ------------------ 96 | * Added travis support 97 | * catkin lint cleanup 98 | * Switched travis to jade branch 99 | * Contributors: Dave Coleman 100 | 101 | 0.0.2 (2015-12-03) 102 | ------------------ 103 | * Initial release 104 | * Contributors: Dave Coleman 105 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(rosparam_shortcuts) 3 | 4 | # C++ 14 5 | add_compile_options(-std=c++14) 6 | 7 | find_package(catkin REQUIRED COMPONENTS 8 | roscpp 9 | cmake_modules 10 | eigen_conversions # TODO(davetcoleman) remove this dependency, only for build testing 11 | roslint 12 | ) 13 | 14 | find_package(Eigen3 REQUIRED) 15 | 16 | catkin_package( 17 | INCLUDE_DIRS 18 | include 19 | ${EIGEN3_INCLUDE_DIR} 20 | LIBRARIES 21 | ${PROJECT_NAME} 22 | CATKIN_DEPENDS 23 | roscpp 24 | DEPENDS 25 | EIGEN3 26 | ) 27 | 28 | include_directories(SYSTEM 29 | ${EIGEN3_INCLUDE_DIRS} 30 | ) 31 | 32 | include_directories( 33 | include 34 | ${catkin_INCLUDE_DIRS} 35 | ) 36 | 37 | ########### 38 | ## Build ## 39 | ########### 40 | 41 | add_library(${PROJECT_NAME} 42 | src/rosparam_shortcuts.cpp 43 | ) 44 | 45 | target_link_libraries(${PROJECT_NAME} 46 | ${catkin_LIBRARIES} 47 | ) 48 | 49 | ## Example executable 50 | add_executable(${PROJECT_NAME}_example src/example.cpp) 51 | set_target_properties(${PROJECT_NAME}_example PROPERTIES OUTPUT_NAME example PREFIX "") 52 | target_link_libraries(${PROJECT_NAME}_example 53 | ${PROJECT_NAME} 54 | ${catkin_LIBRARIES} 55 | ) 56 | 57 | ############# 58 | ## Testing ## 59 | ############# 60 | 61 | ## Test for correct C++ source code 62 | ## To run: catkin bot --make-args roslint 63 | roslint_cpp() 64 | 65 | ############# 66 | ## Install ## 67 | ############# 68 | 69 | # Mark cpp header files for installation 70 | install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_example 71 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 72 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 73 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 74 | ) 75 | 76 | # Mark cpp header files for installation 77 | install(DIRECTORY include/${PROJECT_NAME}/ 78 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 79 | FILES_MATCHING PATTERN "*.h" 80 | PATTERN ".svn" EXCLUDE 81 | ) 82 | 83 | # Mark roslaunch files for installation 84 | install(DIRECTORY launch/ 85 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 86 | FILES_MATCHING PATTERN "*.launch" 87 | PATTERN ".svn" EXCLUDE 88 | ) 89 | 90 | # Mark config files for installation 91 | install(DIRECTORY config/ 92 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 93 | FILES_MATCHING PATTERN "*.yaml" 94 | PATTERN ".svn" EXCLUDE 95 | ) 96 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # ROS Param Shortcuts 2 | 3 | Quickly load variables from rosparam with good command line error checking. 4 | 5 | This package enforces the philosophy that there should be no default parameters - everything must be defined by the user in yaml files (or launch files or where ever) otherwise your program should not run. This helps debug why something isn't working correctly - it will tell you exactly what rosparameters are missing. 6 | 7 | Features: 8 | - Outputs all loaded data into consule using ROS_DEBUG, so you won't see it unless you turn it on 9 | - Namespaces all output within the ``parent_name`` 10 | - Great for having each class have its own parameter namespace 11 | - Helpful error messages if parameter is missing, explaining where it expects to find it 12 | - Removes lots of repetitious code 13 | - Supports datatypes that rosparam does not by default, such as std::size_t, ros::Duration, Eigen::Isometry3d, Eigen::Affine3d (deprecated) 14 | - Supports loading std::vectors easily, and debugging that data 15 | - Supports loading an entire list of bool parameters 16 | 17 | 18 | 19 | This open source project was developed at [PickNik Robotics](https://picknik.ai/). Need professional ROS development and consulting? Contact us at projects@picknik.ai for a free consultation. 20 | 21 | ## Status: 22 | 23 | * [![Build Status](https://api.travis-ci.org/PickNikRobotics/rosparam_shortcuts.svg?branch=melodic-devel)](https://travis-ci.org/PickNikRobotics/rosparam_shortcuts) Travis - Continuous Integration (Melodic) 24 | * [![Build Status](https://api.travis-ci.org/PickNikRobotics/rosparam_shortcuts.svg?branch=kinetic-devel)](https://travis-ci.org/PickNikRobotics/rosparam_shortcuts) Travis - Continuous Integration (Kinetic) 25 | * [![Build Status](http://build.ros.org/buildStatus/icon?job=Msrc_uB__rosparam_shortcuts__ubuntu_bionic__source)](http://build.ros.org/view/Msrc_uB/job/Msrc_uB__rosparam_shortcuts__ubuntu_bionic__source/) ROS Buildfarm - Bionic - Melodic Devel - Source Build 26 | * [![Build Status](http://build.ros.org/buildStatus/icon?job=Mbin_uB64__rosparam_shortcuts__ubuntu_bionic_amd64__binary)](http://build.ros.org/view/Mbin_uB64/job/Mbin_uB64__rosparam_shortcuts__ubuntu_bionic_amd64__binary/) ROS Buildfarm - AMD64 Bionic - Melodic Devel - Debian Build 27 | * [![Build Status](http://build.ros.org/buildStatus/icon?job=Ksrc_uX__rosparam_shortcuts__ubuntu_xenial__source)](http://build.ros.org/view/Ksrc_uX/job/Ksrc_uX__rosparam_shortcuts__ubuntu_xenial__source/) ROS Buildfarm - Xenial - Kinetic Devel - Source Build 28 | * [![Build Status](http://build.ros.org/buildStatus/icon?job=Kbin_uX64__rosparam_shortcuts__ubuntu_xenial_amd64__binary)](http://build.ros.org/view/Kbin_uX64/job/Kbin_uX64__rosparam_shortcuts__ubuntu_xenial_amd64__binary/) ROS Buildfarm - AMD64 Xenial - Kinetic Devel - Debian Build 29 | ## Install 30 | 31 | ### Ubuntu Debian 32 | 33 | `rosparam_shortcuts` is currently only released for ROS Kinetic and Melodic. For other ROS releases, you may need to build `rosparam_shortcuts` from source. 34 | 35 | sudo apt-get install ros-$ROS_DISTRO-rosparam-shortcuts 36 | 37 | ### Build from Source 38 | 39 | To build this package, ``git clone`` this repo into a [catkin workspace](http://wiki.ros.org/catkin/Tutorials/create_a_workspace) and be sure to install necessary dependencies by running the following command in the root of your catkin workspace: 40 | 41 | rosdep install -y --from-paths src --ignore-src --rosdistro $ROS_DISTRO 42 | 43 | ## Code API 44 | 45 | See [Class Reference](http://docs.ros.org/kinetic/api/rosparam_shortcuts/html/) 46 | 47 | ## Usage / Demo 48 | 49 | See the file ``src/example.cpp`` for example code. To run: 50 | 51 | roslaunch rosparam_shortcuts example.launch 52 | 53 | Your yaml file would look something like the file ``config/example.yaml``: 54 | 55 | ``` 56 | example: 57 | control_rate: 100.0 # double 58 | param1: 20 # int 59 | param2: 30 # size_t 60 | param3: 1 # ros::Duration 61 | param4: [1, 1, 1, 3.14, 0, 0] # Eigen::Isometry3d - x, y, z, roll, pitch, yaw 62 | param5: [1.1, 2.2, 3.3, 4.4] # std::vector 63 | param6: [2, 2, 2, 1, 0, 0, 0] # Eigen::Isometry3d - x, y, z, qw, qx, qy, qz 64 | param7: [1, 1, 1, 3.14, 0, 0] # geometry_msgs::Pose - x, y, z, roll, pitch, yaw 65 | param8: [2, 2, 2, 1, 0, 0, 0] # geometry_msgs::Pose - x, y, z, qw, qx, qy, qz 66 | ``` 67 | 68 | ## Testing and Linting 69 | 70 | To run [roslint](http://wiki.ros.org/roslint), use the following command with [catkin-tools](https://catkin-tools.readthedocs.org/): 71 | 72 | catkin build --no-status --no-deps --this --make-args roslint 73 | 74 | To run [catkin lint](https://pypi.python.org/pypi/catkin_lint), use the following command with [catkin-tools](https://catkin-tools.readthedocs.org/): 75 | 76 | catkin lint -W2 77 | 78 | There are currently no unit or integration tests for this package. If there were you would use the following command with [catkin-tools](https://catkin-tools.readthedocs.org/): 79 | 80 | catkin run_tests --no-deps --this -i 81 | 82 | ## Contribute 83 | 84 | Please send PRs for new helper functions, fixes, etc! 85 | -------------------------------------------------------------------------------- /config/example.yaml: -------------------------------------------------------------------------------- 1 | example: 2 | control_rate: 100.0 # double 3 | param1: 20 # int 4 | param2: 30 # size_t 5 | param3: 1 # ros::Duration 6 | param4: [1, 1, 1, 3.14, 0, 0] # Eigen::Isometry3d - x, y, z, roll, pitch, yaw 7 | param5: [1.1, 2.2, 3.3, 4.4] # std::vector 8 | param6: [2, 2, 2, 1, 0, 0, 0] # Eigen::Isometry3d - x, y, z, qw, qx, qy, qz 9 | param7: [1, 1, 1, 3.14, 0, 0] # geometry_msgs::Pose - x, y, z, roll, pitch, yaw 10 | param8: [2, 2, 2, 1, 0, 0, 0] # geometry_msgs::Pose - x, y, z, qw, qx, qy, qz 11 | -------------------------------------------------------------------------------- /include/rosparam_shortcuts/deprecation.h: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2012, Willow Garage, Inc. 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of Willow Garage nor the names of its 18 | * contributors may be used to endorse or promote products derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | *********************************************************************/ 34 | 35 | #ifndef ROSPARAM_SHORTCUTS_DEPRECATION_H 36 | #define ROSPARAM_SHORTCUTS_DEPRECATION_H 37 | 38 | /** \def ROSPARAM_SHORTCUTS_DEPRECATED 39 | Macro that marks functions as deprecated */ 40 | 41 | #ifdef __GNUC__ 42 | #define ROSPARAM_SHORTCUTS_DEPRECATED __attribute__((deprecated)) 43 | #elif defined(_MSC_VER) 44 | #define ROSPARAM_SHORTCUTS_DEPRECATED __declspec(deprecated) 45 | #elif defined(__clang__) 46 | #define ROSPARAM_SHORTCUTS_DEPRECATED __attribute__((deprecated("Use of this method is deprecated"))) 47 | #else 48 | #define ROSPARAM_SHORTCUTS_DEPRECATED /* Nothing */ 49 | #endif 50 | 51 | #endif // ROSPARAM_SHORTCUTS_DEPRECATION_H 52 | -------------------------------------------------------------------------------- /include/rosparam_shortcuts/rosparam_shortcuts.h: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2015, University of Colorado, Boulder 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of the Univ of CO, Boulder nor the names of its 18 | * contributors may be used to endorse or promote products derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | *********************************************************************/ 34 | 35 | /* Author: Dave Coleman 36 | Desc: Helpers for loading parameters from the parameter server 37 | */ 38 | 39 | #ifndef ROSPARAM_SHORTCUTS_ROSPARAM_SHORTCUTS_H 40 | #define ROSPARAM_SHORTCUTS_ROSPARAM_SHORTCUTS_H 41 | 42 | // C++ 43 | #include 44 | #include 45 | #include 46 | 47 | // ROS 48 | #include 49 | 50 | // Eigen 51 | #include 52 | 53 | // this package 54 | #include 55 | 56 | // geometry_msgs/Pose 57 | #include 58 | 59 | namespace rosparam_shortcuts 60 | { 61 | // ------------------------------------------------------------------------------------------------- 62 | // Helper Functions 63 | // ------------------------------------------------------------------------------------------------- 64 | 65 | /** 66 | * \brief Get a paremeter from the ROS param server. Note that does not provide for default values 67 | * \param parent_name - the name of the class that is calling this function, used for filtering out logging output by 68 | * namespacing it 69 | * \param nh - a ROS node handle 70 | * \param param_name - name of parameter to get 71 | * \param value - resulting loaded values, or no change if error (function returns false) 72 | * \return true on success 73 | */ 74 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, bool &value); 75 | 76 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶ms_name, 77 | std::map ¶meters); 78 | 79 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, double &value); 80 | 81 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, 82 | std::vector &values); 83 | 84 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, int &value); 85 | 86 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::size_t &value); 87 | 88 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::string &value); 89 | 90 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, 91 | std::vector &values); 92 | 93 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, 94 | ros::Duration &value); 95 | 96 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, 97 | Eigen::Isometry3d &value); 98 | 99 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, 100 | geometry_msgs::Pose &value); 101 | 102 | /** 103 | * \brief Output a string of values from an array for debugging 104 | * \param array of values 105 | * \return string of numbers separated by commas 106 | */ 107 | std::string getDebugArrayString(std::vector values); 108 | 109 | std::string getDebugArrayString(std::vector values); 110 | 111 | /** 112 | * \brief Convert from 6 doubles of [x,y,z] [r,p,y] or 7 doubles of [x, y, z, qw, qx, qy, qz] to a transform 113 | * \return true on success 114 | */ 115 | bool convertDoublesToEigen(const std::string &parent_name, std::vector values, Eigen::Isometry3d &transform); 116 | 117 | /** 118 | * \brief Check that there were no errors, and if there were, shutdown 119 | * \param error - total number of errors found 120 | */ 121 | void shutdownIfError(const std::string &parent_name, std::size_t error_count); 122 | 123 | } // namespace rosparam_shortcuts 124 | 125 | #endif // ROSPARAM_SHORTCUTS_ROSPARAM_SHORTCUTS_H 126 | -------------------------------------------------------------------------------- /launch/example.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | rosparam_shortcuts 4 | 0.3.3 5 | Quickly load variables from rosparam with good command line error checking. 6 | 7 | Dave Coleman 8 | 9 | BSD 10 | 11 | https://github.com/davetcoleman/rosparam_shortcuts 12 | https://github.com/davetcoleman/rosparam_shortcuts/issues 13 | https://github.com/davetcoleman/rosparam_shortcuts/ 14 | 15 | Dave Coleman 16 | 17 | catkin 18 | 19 | roscpp 20 | cmake_modules 21 | eigen 22 | eigen_conversions 23 | roslint 24 | 25 | roscpp 26 | eigen_conversions 27 | 28 | 29 | 30 | 31 | -------------------------------------------------------------------------------- /src/example.cpp: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2015, PickNik LLC 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of PickNik LLC nor the names of its 18 | * contributors may be used to endorse or promote products derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | *********************************************************************/ 34 | 35 | /* Author: Dave Coleman 36 | Desc: Example of how to use rosparam_shorcuts 37 | */ 38 | 39 | // C++ 40 | #include 41 | #include 42 | 43 | // ROS 44 | #include 45 | 46 | // ROS parameter loading 47 | #include 48 | 49 | int main(int argc, char** argv) 50 | { 51 | std::string name = "example"; 52 | ros::init(argc, argv, name); 53 | ros::NodeHandle nh; 54 | ROS_INFO_STREAM_NAMED(name, "Starting rosparam shortcuts example..."); 55 | 56 | // Allow the action server to recieve and send ros messages 57 | ros::AsyncSpinner spinner(2); 58 | spinner.start(); 59 | 60 | double control_rate; 61 | int param1; 62 | std::size_t param2; 63 | ros::Duration param3; 64 | Eigen::Isometry3d param4; 65 | std::vector param5; 66 | Eigen::Isometry3d param6; 67 | geometry_msgs::Pose param7; 68 | geometry_msgs::Pose param8; 69 | 70 | // Load rosparams 71 | ros::NodeHandle rpnh(nh, name); 72 | std::size_t error = 0; 73 | error += !rosparam_shortcuts::get(name, rpnh, "control_rate", control_rate); // Double param 74 | error += !rosparam_shortcuts::get(name, rpnh, "param1", param1); // Int param 75 | error += !rosparam_shortcuts::get(name, rpnh, "param2", param2); // SizeT param 76 | error += !rosparam_shortcuts::get(name, rpnh, "param3", param3); // Duration param 77 | error += !rosparam_shortcuts::get(name, rpnh, "param4", param4); // Isometry3d param 78 | error += !rosparam_shortcuts::get(name, rpnh, "param5", param5); // std::vector 79 | error += !rosparam_shortcuts::get(name, rpnh, "param6", param6); // Isometry3d param 80 | error += !rosparam_shortcuts::get(name, rpnh, "param7", param7); // geometry_msgs::Pose param 81 | error += !rosparam_shortcuts::get(name, rpnh, "param8", param8); // geometry_msgs::Pose param 82 | // add more parameters here to load if desired 83 | rosparam_shortcuts::shutdownIfError(name, error); 84 | 85 | // Output values that were read in 86 | ROS_INFO_STREAM_NAMED(name, "control rate: " << control_rate); 87 | ROS_INFO_STREAM_NAMED(name, "param1: " << param1); 88 | ROS_INFO_STREAM_NAMED(name, "param2: " << param2); 89 | ROS_INFO_STREAM_NAMED(name, "param3: " << param3.toSec()); 90 | ROS_INFO_STREAM_NAMED(name, "param4: Translation:\n" << param4.translation()); 91 | ROS_INFO_STREAM_NAMED(name, "param5[0]: " << param5[0]); 92 | ROS_INFO_STREAM_NAMED(name, "param5[3]: " << param5[3]); 93 | ROS_INFO_STREAM_NAMED(name, "param6: Translation:\n" << param6.translation()); 94 | ROS_INFO_STREAM_NAMED(name, "param7: Pose:\n" << param7); 95 | ROS_INFO_STREAM_NAMED(name, "param8: Pose:\n" << param8); 96 | ROS_INFO_STREAM_NAMED(name, "Shutting down."); 97 | ros::shutdown(); 98 | 99 | return 0; 100 | } 101 | -------------------------------------------------------------------------------- /src/rosparam_shortcuts.cpp: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2015, University of Colorado, Boulder 5 | * All rights reserved. 6 | * 7 | * Redistribution and use in source and binary forms, with or without 8 | * modification, are permitted provided that the following conditions 9 | * are met: 10 | * 11 | * * Redistributions of source code must retain the above copyright 12 | * notice, this list of conditions and the following disclaimer. 13 | * * Redistributions in binary form must reproduce the above 14 | * copyright notice, this list of conditions and the following 15 | * disclaimer in the documentation and/or other materials provided 16 | * with the distribution. 17 | * * Neither the name of the Univ of CO, Boulder nor the names of its 18 | * contributors may be used to endorse or promote products derived 19 | * from this software without specific prior written permission. 20 | * 21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 32 | * POSSIBILITY OF SUCH DAMAGE. 33 | *********************************************************************/ 34 | 35 | /* Author: Dave Coleman 36 | Desc: Helpers for loading parameters from the parameter server 37 | */ 38 | 39 | // C++ 40 | #include 41 | #include 42 | #include 43 | 44 | // this package 45 | #include 46 | 47 | // Eigen/TF conversion 48 | #include 49 | 50 | namespace rosparam_shortcuts 51 | { 52 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, bool &value) 53 | { 54 | // Load a param 55 | if (!nh.hasParam(param_name)) 56 | { 57 | ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'."); 58 | return false; 59 | } 60 | nh.getParam(param_name, value); 61 | ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name << "' with value " 62 | << value); 63 | 64 | return true; 65 | } 66 | 67 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶ms_namespace, 68 | std::map ¶meters) 69 | { 70 | // Load a param 71 | if (!nh.hasParam(params_namespace)) 72 | { 73 | ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameters in namespace '" << nh.getNamespace() << "/" 74 | << params_namespace << "'."); 75 | return false; 76 | } 77 | nh.getParam(params_namespace, parameters); 78 | 79 | // Debug 80 | for (std::map::const_iterator param_it = parameters.begin(); param_it != parameters.end(); 81 | param_it++) 82 | { 83 | ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << params_namespace << "/" 84 | << param_it->first << "' with value " << param_it->second); 85 | } 86 | 87 | return true; 88 | } 89 | 90 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, double &value) 91 | { 92 | // Load a param 93 | if (!nh.hasParam(param_name)) 94 | { 95 | ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'."); 96 | return false; 97 | } 98 | nh.getParam(param_name, value); 99 | ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name << "' with value " 100 | << value); 101 | 102 | return true; 103 | } 104 | 105 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, 106 | std::vector &values) 107 | { 108 | // Load a param 109 | if (!nh.hasParam(param_name)) 110 | { 111 | ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'."); 112 | return false; 113 | } 114 | nh.getParam(param_name, values); 115 | 116 | if (values.empty()) 117 | ROS_WARN_STREAM_NAMED(parent_name, "Empty vector for parameter '" << nh.getNamespace() << "/" << param_name << "'" 118 | "."); 119 | 120 | ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name 121 | << "' with values [" << getDebugArrayString(values) << "]"); 122 | 123 | return true; 124 | } 125 | 126 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, int &value) 127 | { 128 | // Load a param 129 | if (!nh.hasParam(param_name)) 130 | { 131 | ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'."); 132 | return false; 133 | } 134 | nh.getParam(param_name, value); 135 | ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name << "' with value " 136 | << value); 137 | 138 | return true; 139 | } 140 | 141 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::size_t &value) 142 | { 143 | // Load a param 144 | if (!nh.hasParam(param_name)) 145 | { 146 | ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'."); 147 | return false; 148 | } 149 | int nonsigned_value; 150 | nh.getParam(param_name, nonsigned_value); 151 | value = nonsigned_value; 152 | ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name << "' with value " 153 | << value); 154 | 155 | return true; 156 | } 157 | 158 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::string &value) 159 | { 160 | // Load a param 161 | if (!nh.hasParam(param_name)) 162 | { 163 | ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'."); 164 | return false; 165 | } 166 | nh.getParam(param_name, value); 167 | ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name << "' with value " 168 | << value); 169 | 170 | return true; 171 | } 172 | 173 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, 174 | std::vector &values) 175 | { 176 | // Load a param 177 | if (!nh.hasParam(param_name)) 178 | { 179 | ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'."); 180 | return false; 181 | } 182 | nh.getParam(param_name, values); 183 | 184 | if (values.empty()) 185 | ROS_WARN_STREAM_NAMED(parent_name, "Empty vector for parameter '" << nh.getNamespace() << "/" << param_name << "'" 186 | "."); 187 | 188 | ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name << "' with value " 189 | << getDebugArrayString(values)); 190 | 191 | return true; 192 | } 193 | 194 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, ros::Duration &value) 195 | { 196 | double temp_value; 197 | // Load a param 198 | if (!nh.hasParam(param_name)) 199 | { 200 | ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'."); 201 | return false; 202 | } 203 | nh.getParam(param_name, temp_value); 204 | ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name << "' with value " 205 | << value); 206 | 207 | // Convert to ros::Duration 208 | value = ros::Duration(temp_value); 209 | 210 | return true; 211 | } 212 | 213 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, 214 | Eigen::Isometry3d &value) 215 | { 216 | std::vector values; 217 | 218 | // Load a param 219 | if (!nh.hasParam(param_name)) 220 | { 221 | ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'."); 222 | return false; 223 | } 224 | nh.getParam(param_name, values); 225 | 226 | if (values.empty()) 227 | ROS_WARN_STREAM_NAMED(parent_name, "Empty vector for parameter '" << nh.getNamespace() << "/" << param_name << "'" 228 | "."); 229 | 230 | ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name 231 | << "' with values [" << getDebugArrayString(values) << "]"); 232 | 233 | // Convert to Eigen::Isometry3d 234 | convertDoublesToEigen(parent_name, values, value); 235 | 236 | return true; 237 | } 238 | 239 | bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, 240 | geometry_msgs::Pose &value) 241 | { 242 | Eigen::Isometry3d eigen_pose; 243 | if (!get(parent_name, nh, param_name, eigen_pose)) 244 | return false; 245 | 246 | tf::poseEigenToMsg(eigen_pose, value); 247 | return true; 248 | } 249 | 250 | std::string getDebugArrayString(std::vector values) 251 | { 252 | std::stringstream debug_values; 253 | for (std::size_t i = 0; i < values.size(); ++i) 254 | { 255 | debug_values << values[i] << ","; 256 | } 257 | return debug_values.str(); 258 | } 259 | 260 | std::string getDebugArrayString(std::vector values) 261 | { 262 | std::stringstream debug_values; 263 | for (std::size_t i = 0; i < values.size(); ++i) 264 | { 265 | debug_values << values[i] << ","; 266 | } 267 | return debug_values.str(); 268 | } 269 | 270 | bool convertDoublesToEigen(const std::string &parent_name, std::vector values, Eigen::Isometry3d &transform) 271 | { 272 | if (values.size() == 6) 273 | { 274 | // This version is correct RPY 275 | Eigen::AngleAxisd roll_angle(values[3], Eigen::Vector3d::UnitX()); 276 | Eigen::AngleAxisd pitch_angle(values[4], Eigen::Vector3d::UnitY()); 277 | Eigen::AngleAxisd yaw_angle(values[5], Eigen::Vector3d::UnitZ()); 278 | Eigen::Quaternion quaternion = roll_angle * pitch_angle * yaw_angle; 279 | 280 | transform = Eigen::Translation3d(values[0], values[1], values[2]) * quaternion; 281 | 282 | return true; 283 | } 284 | else if (values.size() == 7) 285 | { 286 | // Quaternion 287 | transform = Eigen::Translation3d(values[0], values[1], values[2]) * 288 | Eigen::Quaterniond(values[3], values[4], values[5], values[6]); 289 | return true; 290 | } 291 | else 292 | { 293 | ROS_ERROR_STREAM_NAMED(parent_name, "Invalid number of doubles provided for transform, size=" << values.size()); 294 | return false; 295 | } 296 | } 297 | 298 | void shutdownIfError(const std::string &parent_name, std::size_t error_count) 299 | { 300 | if (!error_count) 301 | return; 302 | 303 | ROS_ERROR_STREAM_NAMED(parent_name, "Missing " << error_count << " ros parameters that are required. Shutting down " 304 | "to prevent undefined behaviors"); 305 | ros::shutdown(); 306 | exit(0); 307 | } 308 | 309 | } // namespace rosparam_shortcuts 310 | --------------------------------------------------------------------------------