[
  {
    "path": ".gitignore",
    "content": "# -*- mode: gitignore; -*-\n*~\n\\#*\\#\n"
  },
  {
    "path": "ackermann_cmd_mux/.cproject",
    "content": "<?xml version=\"1.0\" encoding=\"UTF-8\" standalone=\"no\"?>\n<?fileVersion 4.0.0?><cproject storage_type_id=\"org.eclipse.cdt.core.XmlProjectDescriptionStorage\">\n\t<storageModule moduleId=\"org.eclipse.cdt.core.settings\">\n\t\t<cconfiguration id=\"cdt.managedbuild.toolchain.gnu.base.1612295671\">\n\t\t\t<storageModule buildSystemId=\"org.eclipse.cdt.managedbuilder.core.configurationDataProvider\" id=\"cdt.managedbuild.toolchain.gnu.base.1612295671\" moduleId=\"org.eclipse.cdt.core.settings\" name=\"Default\">\n\t\t\t\t<externalSettings/>\n\t\t\t\t<extensions>\n\t\t\t\t\t<extension id=\"org.eclipse.cdt.core.GmakeErrorParser\" point=\"org.eclipse.cdt.core.ErrorParser\"/>\n\t\t\t\t\t<extension id=\"org.eclipse.cdt.core.CWDLocator\" point=\"org.eclipse.cdt.core.ErrorParser\"/>\n\t\t\t\t\t<extension id=\"org.eclipse.cdt.core.GCCErrorParser\" point=\"org.eclipse.cdt.core.ErrorParser\"/>\n\t\t\t\t\t<extension id=\"org.eclipse.cdt.core.GASErrorParser\" point=\"org.eclipse.cdt.core.ErrorParser\"/>\n\t\t\t\t\t<extension id=\"org.eclipse.cdt.core.GLDErrorParser\" point=\"org.eclipse.cdt.core.ErrorParser\"/>\n\t\t\t\t\t<extension id=\"org.eclipse.cdt.core.ELF\" point=\"org.eclipse.cdt.core.BinaryParser\"/>\n\t\t\t\t</extensions>\n\t\t\t</storageModule>\n\t\t\t<storageModule moduleId=\"cdtBuildSystem\" version=\"4.0.0\">\n\t\t\t\t<configuration buildProperties=\"\" description=\"\" id=\"cdt.managedbuild.toolchain.gnu.base.1612295671\" name=\"Default\" parent=\"org.eclipse.cdt.build.core.emptycfg\">\n\t\t\t\t\t<folderInfo id=\"cdt.managedbuild.toolchain.gnu.base.1612295671.1777191576\" name=\"/\" resourcePath=\"\">\n\t\t\t\t\t\t<toolChain id=\"cdt.managedbuild.toolchain.gnu.base.520406189\" name=\"cdt.managedbuild.toolchain.gnu.base\" superClass=\"cdt.managedbuild.toolchain.gnu.base\">\n\t\t\t\t\t\t\t<targetPlatform archList=\"all\" binaryParser=\"org.eclipse.cdt.core.ELF\" id=\"cdt.managedbuild.target.gnu.platform.base.778880296\" name=\"Debug Platform\" osList=\"linux,hpux,aix,qnx\" superClass=\"cdt.managedbuild.target.gnu.platform.base\"/>\n\t\t\t\t\t\t\t<builder arguments=\"-f ${YUJIN_WORKSPACE}/build/yujin_ocs/${ProjName}/Makefile -j8\" command=\"make\" id=\"cdt.managedbuild.target.gnu.builder.base.1328555746\" keepEnvironmentInBuildfile=\"false\" managedBuildOn=\"false\" name=\"Gnu Make Builder\" superClass=\"cdt.managedbuild.target.gnu.builder.base\"/>\n\t\t\t\t\t\t\t<tool id=\"cdt.managedbuild.tool.gnu.archiver.base.1304797274\" name=\"GCC Archiver\" superClass=\"cdt.managedbuild.tool.gnu.archiver.base\"/>\n\t\t\t\t\t\t\t<tool id=\"cdt.managedbuild.tool.gnu.cpp.compiler.base.1243660247\" name=\"GCC C++ Compiler\" superClass=\"cdt.managedbuild.tool.gnu.cpp.compiler.base\">\n\t\t\t\t\t\t\t\t<inputType id=\"cdt.managedbuild.tool.gnu.cpp.compiler.input.991921373\" superClass=\"cdt.managedbuild.tool.gnu.cpp.compiler.input\"/>\n\t\t\t\t\t\t\t</tool>\n\t\t\t\t\t\t\t<tool id=\"cdt.managedbuild.tool.gnu.c.compiler.base.1000098092\" name=\"GCC C Compiler\" superClass=\"cdt.managedbuild.tool.gnu.c.compiler.base\">\n\t\t\t\t\t\t\t\t<inputType id=\"cdt.managedbuild.tool.gnu.c.compiler.input.7779663\" superClass=\"cdt.managedbuild.tool.gnu.c.compiler.input\"/>\n\t\t\t\t\t\t\t</tool>\n\t\t\t\t\t\t\t<tool id=\"cdt.managedbuild.tool.gnu.c.linker.base.176134653\" name=\"GCC C Linker\" superClass=\"cdt.managedbuild.tool.gnu.c.linker.base\"/>\n\t\t\t\t\t\t\t<tool id=\"cdt.managedbuild.tool.gnu.cpp.linker.base.370153349\" name=\"GCC C++ Linker\" superClass=\"cdt.managedbuild.tool.gnu.cpp.linker.base\">\n\t\t\t\t\t\t\t\t<inputType id=\"cdt.managedbuild.tool.gnu.cpp.linker.input.494129810\" superClass=\"cdt.managedbuild.tool.gnu.cpp.linker.input\">\n\t\t\t\t\t\t\t\t\t<additionalInput kind=\"additionalinputdependency\" paths=\"$(USER_OBJS)\"/>\n\t\t\t\t\t\t\t\t\t<additionalInput kind=\"additionalinput\" paths=\"$(LIBS)\"/>\n\t\t\t\t\t\t\t\t</inputType>\n\t\t\t\t\t\t\t</tool>\n\t\t\t\t\t\t\t<tool id=\"cdt.managedbuild.tool.gnu.assembler.base.1233806798\" name=\"GCC Assembler\" superClass=\"cdt.managedbuild.tool.gnu.assembler.base\">\n\t\t\t\t\t\t\t\t<inputType id=\"cdt.managedbuild.tool.gnu.assembler.input.1933798163\" superClass=\"cdt.managedbuild.tool.gnu.assembler.input\"/>\n\t\t\t\t\t\t\t</tool>\n\t\t\t\t\t\t</toolChain>\n\t\t\t\t\t</folderInfo>\n\t\t\t\t\t<sourceEntries>\n\t\t\t\t\t\t<entry flags=\"VALUE_WORKSPACE_PATH\" kind=\"sourcePath\" name=\"src\"/>\n\t\t\t\t\t\t<entry flags=\"VALUE_WORKSPACE_PATH\" kind=\"sourcePath\" name=\"include/ackermann_cmd_mux\"/>\n\t\t\t\t\t</sourceEntries>\n\t\t\t\t</configuration>\n\t\t\t</storageModule>\n\t\t\t<storageModule moduleId=\"org.eclipse.cdt.core.externalSettings\"/>\n\t\t</cconfiguration>\n\t</storageModule>\n\t<storageModule moduleId=\"cdtBuildSystem\" version=\"4.0.0\">\n\t\t<project id=\"ackermann_cmd_mux.null.53888827\" name=\"ackermann_cmd_mux\"/>\n\t</storageModule>\n\t<storageModule moduleId=\"scannerConfiguration\">\n\t\t<autodiscovery enabled=\"true\" problemReportingEnabled=\"true\" selectedProfileId=\"\"/>\n\t\t<scannerConfigBuildInfo instanceId=\"cdt.managedbuild.toolchain.gnu.base.1612295671;cdt.managedbuild.toolchain.gnu.base.1612295671.1777191576;cdt.managedbuild.tool.gnu.c.compiler.base.1000098092;cdt.managedbuild.tool.gnu.c.compiler.input.7779663\">\n\t\t\t<autodiscovery enabled=\"true\" problemReportingEnabled=\"true\" selectedProfileId=\"org.eclipse.cdt.managedbuilder.core.GCCManagedMakePerProjectProfileC\"/>\n\t\t</scannerConfigBuildInfo>\n\t\t<scannerConfigBuildInfo instanceId=\"cdt.managedbuild.toolchain.gnu.base.1612295671;cdt.managedbuild.toolchain.gnu.base.1612295671.1777191576;cdt.managedbuild.tool.gnu.cpp.compiler.base.1243660247;cdt.managedbuild.tool.gnu.cpp.compiler.input.991921373\">\n\t\t\t<autodiscovery enabled=\"true\" problemReportingEnabled=\"true\" selectedProfileId=\"org.eclipse.cdt.managedbuilder.core.GCCManagedMakePerProjectProfileCPP\"/>\n\t\t</scannerConfigBuildInfo>\n\t</storageModule>\n\t<storageModule moduleId=\"refreshScope\" versionNumber=\"2\">\n\t\t<configuration configurationName=\"Default\">\n\t\t\t<resource resourceType=\"PROJECT\" workspacePath=\"/ackermann_cmd_mux\"/>\n\t\t</configuration>\n\t</storageModule>\n\t<storageModule moduleId=\"org.eclipse.cdt.core.LanguageSettingsProviders\"/>\n</cproject>\n"
  },
  {
    "path": "ackermann_cmd_mux/.gitignore",
    "content": "/bin\n/build\n/lib\n"
  },
  {
    "path": "ackermann_cmd_mux/.project",
    "content": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<projectDescription>\n\t<name>ackermann_cmd_mux</name>\n\t<comment></comment>\n\t<projects>\n\t</projects>\n\t<buildSpec>\n\t\t<buildCommand>\n\t\t\t<name>org.python.pydev.PyDevBuilder</name>\n\t\t\t<arguments>\n\t\t\t</arguments>\n\t\t</buildCommand>\n\t\t<buildCommand>\n\t\t\t<name>org.eclipse.cdt.managedbuilder.core.genmakebuilder</name>\n\t\t\t<triggers>clean,full,incremental,</triggers>\n\t\t\t<arguments>\n\t\t\t\t<dictionary>\n\t\t\t\t\t<key>?name?</key>\n\t\t\t\t\t<value></value>\n\t\t\t\t</dictionary>\n\t\t\t\t<dictionary>\n\t\t\t\t\t<key>org.eclipse.cdt.make.core.append_environment</key>\n\t\t\t\t\t<value>true</value>\n\t\t\t\t</dictionary>\n\t\t\t\t<dictionary>\n\t\t\t\t\t<key>org.eclipse.cdt.make.core.autoBuildTarget</key>\n\t\t\t\t\t<value>all</value>\n\t\t\t\t</dictionary>\n\t\t\t\t<dictionary>\n\t\t\t\t\t<key>org.eclipse.cdt.make.core.buildArguments</key>\n\t\t\t\t\t<value></value>\n\t\t\t\t</dictionary>\n\t\t\t\t<dictionary>\n\t\t\t\t\t<key>org.eclipse.cdt.make.core.buildCommand</key>\n\t\t\t\t\t<value>make</value>\n\t\t\t\t</dictionary>\n\t\t\t\t<dictionary>\n\t\t\t\t\t<key>org.eclipse.cdt.make.core.cleanBuildTarget</key>\n\t\t\t\t\t<value>clean</value>\n\t\t\t\t</dictionary>\n\t\t\t\t<dictionary>\n\t\t\t\t\t<key>org.eclipse.cdt.make.core.contents</key>\n\t\t\t\t\t<value>org.eclipse.cdt.make.core.activeConfigSettings</value>\n\t\t\t\t</dictionary>\n\t\t\t\t<dictionary>\n\t\t\t\t\t<key>org.eclipse.cdt.make.core.enableAutoBuild</key>\n\t\t\t\t\t<value>false</value>\n\t\t\t\t</dictionary>\n\t\t\t\t<dictionary>\n\t\t\t\t\t<key>org.eclipse.cdt.make.core.enableCleanBuild</key>\n\t\t\t\t\t<value>true</value>\n\t\t\t\t</dictionary>\n\t\t\t\t<dictionary>\n\t\t\t\t\t<key>org.eclipse.cdt.make.core.enableFullBuild</key>\n\t\t\t\t\t<value>true</value>\n\t\t\t\t</dictionary>\n\t\t\t\t<dictionary>\n\t\t\t\t\t<key>org.eclipse.cdt.make.core.fullBuildTarget</key>\n\t\t\t\t\t<value>all</value>\n\t\t\t\t</dictionary>\n\t\t\t\t<dictionary>\n\t\t\t\t\t<key>org.eclipse.cdt.make.core.stopOnError</key>\n\t\t\t\t\t<value>true</value>\n\t\t\t\t</dictionary>\n\t\t\t\t<dictionary>\n\t\t\t\t\t<key>org.eclipse.cdt.make.core.useDefaultBuildCmd</key>\n\t\t\t\t\t<value>true</value>\n\t\t\t\t</dictionary>\n\t\t\t</arguments>\n\t\t</buildCommand>\n\t\t<buildCommand>\n\t\t\t<name>org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder</name>\n\t\t\t<triggers>full,incremental,</triggers>\n\t\t\t<arguments>\n\t\t\t</arguments>\n\t\t</buildCommand>\n\t</buildSpec>\n\t<natures>\n\t\t<nature>org.eclipse.cdt.core.cnature</nature>\n\t\t<nature>org.eclipse.cdt.core.ccnature</nature>\n\t\t<nature>org.eclipse.cdt.managedbuilder.core.managedBuildNature</nature>\n\t\t<nature>org.eclipse.cdt.managedbuilder.core.ScannerConfigNature</nature>\n\t\t<nature>org.python.pydev.pythonNature</nature>\n\t</natures>\n</projectDescription>\n"
  },
  {
    "path": "ackermann_cmd_mux/.pydevproject",
    "content": "<?xml version=\"1.0\" encoding=\"UTF-8\" standalone=\"no\"?>\n<?eclipse-pydev version=\"1.0\"?>\n\n<pydev_project>\n<pydev_property name=\"org.python.pydev.PYTHON_PROJECT_INTERPRETER\">Default</pydev_property>\n<pydev_property name=\"org.python.pydev.PYTHON_PROJECT_VERSION\">python 2.7</pydev_property>\n</pydev_project>\n"
  },
  {
    "path": "ackermann_cmd_mux/.settings/language.settings.xml",
    "content": "<?xml version=\"1.0\" encoding=\"UTF-8\" standalone=\"no\"?>\n<project>\n\t<configuration id=\"cdt.managedbuild.toolchain.gnu.base.1612295671\" name=\"Default\">\n\t\t<extension point=\"org.eclipse.cdt.core.LanguageSettingsProvider\">\n\t\t\t<provider copy-of=\"extension\" id=\"org.eclipse.cdt.ui.UserLanguageSettingsProvider\"/>\n\t\t\t<provider-reference id=\"org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider\" ref=\"shared-provider\"/>\n\t\t\t<provider class=\"org.eclipse.cdt.managedbuilder.language.settings.providers.GCCBuildCommandParser\" id=\"org.eclipse.cdt.managedbuilder.core.GCCBuildCommandParser\" keep-relative-paths=\"false\" name=\"CDT GCC Build Output Parser\" parameter=\"(.*gcc)|(.*[gc]\\+\\+)|(clang)\" prefer-non-shared=\"true\"/>\n\t\t\t<provider-reference id=\"org.eclipse.cdt.managedbuilder.core.GCCBuiltinSpecsDetector\" ref=\"shared-provider\"/>\n\t\t\t<provider-reference id=\"org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider\" ref=\"shared-provider\"/>\n\t\t</extension>\n\t</configuration>\n</project>\n"
  },
  {
    "path": "ackermann_cmd_mux/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package ackermann_cmd_mux\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0.6.3 (2014-12-05)\n------------------\n\n0.6.2 (2014-11-30)\n------------------\n* ackermann_cmd_mux: fixes node handle for output pub\n  to keep backwards compatibility\n* adds a little launcher restructing for muxer and smoother\n* Contributors: Marcus Liebhardt\n\n0.6.0 (2014-07-08)\n------------------\n* updating package informations. remove email for authors. updating maintainer\n* Contributors: Jihoon Lee\n\n0.5.3 (2014-03-24)\n------------------\n* Added support for YAML-CPP 0.5+.\n  The new yaml-cpp API removes the \"node >> outputvar;\" operator, and\n  it has a new way of loading documents. There's no version hint in the\n  library's headers, so I'm getting the version number from pkg-config.\n  This part of the patch is a port of the ones created by @ktossell for\n  map_server and other packages.\n  The new yaml-cpp also does not have FindValue.\n* Contributors: Scott K Logan\n\n0.5.2 (2013-11-05)\n------------------\n\n0.5.1 (2013-10-14)\n------------------\n* Unify naming politics for binaries and plugins.\n\n0.5.0 (2013-10-11)\n------------------\n* Renamed as ackermann_cmd_mux.\n\n0.4.1 (2013-10-08)\n------------------\n\n0.4.0 (2013-08-29)\n------------------\n* Add bugtracker and repo info URLs.\n* Changelogs at package level.\n* License link fixed.\n\n0.3.0 (2013-07-02)\n------------------\n\n0.2.3 (2013-04-15)\n------------------\n\n0.2.2 (2013-02-10)\n------------------\n\n0.2.1 (2013-02-08)\n------------------\n\n0.2.0 (2013-02-07)\n------------------\n* Catkinized.\n\n0.1.3 (2013-01-08)\n------------------\n* More generous description.\n\n0.1.2 (2013-01-02)\n------------------\n* Dynamically reconfigurable.\n* Upgraded to new groovy plugin formats.\n* Add reconfigure launcher and parameter file.\n* Add a dynamic reconfigure script to accept a yaml filename.\n\n0.1.1 (2012-12-21)\n------------------\n\n0.1.0 (2012-12-05)\n------------------\n* Initial version.\n"
  },
  {
    "path": "ackermann_cmd_mux/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(ackermann_cmd_mux)\nfind_package(catkin REQUIRED COMPONENTS \n\troscpp \n\tpluginlib \n\tnodelet \n\tdynamic_reconfigure \n\tackermann_msgs\n\tstd_msgs\n\trospy\n)\n\n# pkg-config support\nfind_package(PkgConfig)\npkg_search_module(yaml-cpp REQUIRED yaml-cpp)\n\nif(NOT ${yaml-cpp_VERSION} VERSION_LESS \"0.5\")\nadd_definitions(-DHAVE_NEW_YAMLCPP)\nendif()\n\n# Dynamic reconfigure support\ngenerate_dynamic_reconfigure_options(cfg/reload.cfg)\n\ncatkin_package(\n   INCLUDE_DIRS include\n   LIBRARIES ${PROJECT_NAME}_nodelet\n   CATKIN_DEPENDS roscpp pluginlib nodelet dynamic_reconfigure ackermann_msgs rospy std_msgs\n   DEPENDS yaml-cpp\n)\n\ninclude_directories(include ${catkin_INCLUDE_DIRS} ${yaml-cpp_INCLUDE_DIRS})\n\n# Nodelet library\nadd_library(${PROJECT_NAME}_nodelet src/ackermann_cmd_mux_nodelet.cpp src/ackermann_cmd_subscribers.cpp)\n#add_dependencies(${PROJECT_NAME}_nodelet ackermann_msgs)\nadd_dependencies(${PROJECT_NAME}_nodelet ${PROJECT_NAME}_gencfg)\n\ntarget_link_libraries(${PROJECT_NAME}_nodelet ${catkin_LIBRARIES} ${yaml-cpp_LIBRARIES})\n\ninstall(TARGETS ${PROJECT_NAME}_nodelet\n        DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n)\ninstall(DIRECTORY include/${PROJECT_NAME}/\n        DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n)\ninstall(DIRECTORY plugins\n        DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\ninstall(DIRECTORY launch\n        DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\ninstall(DIRECTORY param\n        DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n"
  },
  {
    "path": "ackermann_cmd_mux/LICENSE",
    "content": "# Software License Agreement (BSD License)\n#\n# Copyright (c) 2012 Yujin Robot, Daniel Stonier, Jorge Santos\n# All rights reserved.\n#\n# Redistribution and use in source and binary forms, with or without\n# modification, are permitted provided that the following conditions\n# are met:\n#\n#    * Redistributions of source code must retain the above copyright\n#        notice, this list of conditions and the following disclaimer.\n#    * Redistributions in binary form must reproduce the above\n#        copyright notice, this list of conditions and the following\n#        disclaimer in the documentation and/or other materials provided\n#        with the distribution.\n#    * Neither the name of Yujin Robot nor the names of its\n#        contributors may be used to endorse or promote products derived\n#        from this software without specific prior written permission.\n#\n# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n# \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n# POSSIBILITY OF SUCH DAMAGE.\n"
  },
  {
    "path": "ackermann_cmd_mux/cfg/reload.cfg",
    "content": "#!/usr/bin/env python2\n\nPACKAGE = \"ackermann_cmd_mux\"\n\nfrom dynamic_reconfigure.parameter_generator_catkin import *\n\ngen = ParameterGenerator()\n\ngen.add(\"yaml_cfg_file\", str_t, 0, \"Pathname to a yaml file for re-configuration of the mux\", \"\")\n\n# Second arg is node name it will run in (doc purposes only), third is generated filename prefix\nexit(gen.generate(PACKAGE, \"ackermann_cmd_mux_reload\", \"reload\"))\n"
  },
  {
    "path": "ackermann_cmd_mux/include/ackermann_cmd_mux/ackermann_cmd_mux_nodelet.hpp",
    "content": "/**\n * @file /include/ackermann_cmd_mux/ackermann_cmd_mux_nodelet.hpp\n *\n * @brief Structure for the ackermann_cmd_mux.\n *\n * License: BSD\n *   https://raw.github.com/yujinrobot/yujin_ocs/hydro/yocs_ackermann_cmd_mux/LICENSE\n **/\n/*****************************************************************************\n ** Ifdefs\n *****************************************************************************/\n\n#ifndef RACECAR_ACKERMANN_CMD_MUX_HPP_\n#define RACECAR_ACKERMANN_CMD_MUX_HPP_\n\n/*****************************************************************************\n ** Includes\n *****************************************************************************/\n\n#include <ros/ros.h>\n#include <nodelet/nodelet.h>\n#include <dynamic_reconfigure/server.h>\n\n#include \"ackermann_cmd_mux/reloadConfig.h\"\n#include \"ackermann_cmd_mux/ackermann_cmd_subscribers.hpp\"\n\n/*****************************************************************************\n** Namespaces\n*****************************************************************************/\n\nnamespace ackermann_cmd_mux {\n\n/*****************************************************************************\n ** AckermannCmdMux\n *****************************************************************************/\n\nclass AckermannCmdMuxNodelet : public nodelet::Nodelet\n{\npublic:\n  virtual void onInit();\n\n  AckermannCmdMuxNodelet()\n  {\n    dynamic_reconfigure_server = NULL;\n  }\n\n  ~AckermannCmdMuxNodelet()\n  {\n    if (dynamic_reconfigure_server != NULL)\n      delete dynamic_reconfigure_server;\n  }\n\nprivate:\n  AckermannCmdSubscribers ackermann_cmd_sub; /**< Pool of ackermann_cmd topics subscribers */\n  ros::Publisher mux_ackermann_cmd_pub; /**< Multiplexed ackermann command topic */\n  ros::Publisher active_subscriber; /**< Currently allowed ackermann_cmd subscriber */\n\n  void timerCallback(const ros::TimerEvent& event, unsigned int idx);\n  void ackermannCmdCallback(const ackermann_msgs::AckermannDriveStamped::ConstPtr& msg, unsigned int idx);\n\n  /*********************\n  ** Dynamic Reconfigure\n  **********************/\n  dynamic_reconfigure::Server<ackermann_cmd_mux::reloadConfig> * dynamic_reconfigure_server;\n  dynamic_reconfigure::Server<ackermann_cmd_mux::reloadConfig>::CallbackType dynamic_reconfigure_cb;\n  void reloadConfiguration(ackermann_cmd_mux::reloadConfig &config, uint32_t unused_level);\n\n  /*********************\n   ** Private Classes\n   **********************/\n  // Functor assigned to each incoming ackermann command topic to bind it to ackermann_cmd callback\n  class AckermannCmdFunctor\n  {\n  private:\n    unsigned int idx;\n    AckermannCmdMuxNodelet* node;\n\n  public:\n    AckermannCmdFunctor(unsigned int idx, AckermannCmdMuxNodelet* node) :\n        idx(idx), node(node)\n    {\n    }\n\n    void operator()(const ackermann_msgs::AckermannDriveStamped::ConstPtr& msg)\n    {\n      node->ackermannCmdCallback(msg, idx);\n    }\n  };\n\n  // Functor assigned to each ackermann command messages source to bind it to timer callback\n  class TimerFunctor\n  {\n  private:\n    unsigned int idx;\n    AckermannCmdMuxNodelet* node;\n\n  public:\n    TimerFunctor(unsigned int idx, AckermannCmdMuxNodelet* node) :\n        idx(idx), node(node)\n    {\n    }\n\n    void operator()(const ros::TimerEvent& event)\n    {\n      node->timerCallback(event, idx);\n    }\n  };\n};\n\n} // namespace ackermann_cmd_mux\n\n#endif /* RACECAR_ACKERMANN_CMD_MUX_HPP_ */\n"
  },
  {
    "path": "ackermann_cmd_mux/include/ackermann_cmd_mux/ackermann_cmd_subscribers.hpp",
    "content": "/**\n * @file /include/ackermann_cmd_mux/ackermann_cmd_subscribers.hpp\n *\n * @brief Structure for the ackermann_cmd_mux.\n *\n * License: BSD\n *   https://raw.github.com/yujinrobot/yujin_ocs/hydro/yocs_ackermann_cmd_mux/LICENSE\n **/\n/*****************************************************************************\n** Ifdefs\n*****************************************************************************/\n\n#ifndef RACECAR_ACKERMANN_CMD_SUBSCRIBERS_HPP_\n#define RACECAR_ACKERMANN_CMD_SUBSCRIBERS_HPP_\n\n/*****************************************************************************\n** Includes\n*****************************************************************************/\n\n#include <ros/ros.h>\n#include <ackermann_msgs/AckermannDriveStamped.h>\n#include <yaml-cpp/yaml.h>\n\n#ifdef HAVE_NEW_YAMLCPP\n// The >> operator disappeared in yaml-cpp 0.5, so this function is\n// added to provide support for code written under the yaml-cpp 0.3 API.\ntemplate<typename T>\nvoid operator >> (const YAML::Node& node, T& i)\n{\n  i = node.as<T>();\n}\n#endif\n\n/*****************************************************************************\n** Preprocessing\n*****************************************************************************/\n\n// move to a static const?\n#define VACANT  std::numeric_limits<unsigned int>::max()\n\n/*****************************************************************************\n** Namespaces\n*****************************************************************************/\n\nnamespace ackermann_cmd_mux {\n\n/*****************************************************************************\n** AckermannCmdSubscribers\n*****************************************************************************/\n\n/**\n * Pool of ackermann_cmd topics subscribers\n */\nclass AckermannCmdSubscribers\n{\npublic:\n\n  /**\n   * Inner class describing an individual subscriber to a ackermann_cmd topic\n   */\n  class AckermannCmdSubs\n  {\n  public:\n    unsigned int           idx;          /**< Index; assigned according to the order on YAML file */\n    std::string            name;         /**< Descriptive name */\n    ros::Subscriber        subs;         /**< The subscriber itself */\n    std::string            topic;        /**< The name of the topic */\n    ros::Timer             timer;        /**< No incoming messages timeout */\n    double                 timeout;      /**< Timer's timeout, in seconds  */\n    unsigned int           priority;     /**< UNIQUE integer from 0 (lowest priority) to MAX_INT */\n    std::string            short_desc;   /**< Short description (optional) */\n    bool                   active;       /**< Whether this source is active */\n\n    AckermannCmdSubs(unsigned int idx) : idx(idx), active(false) {};\n\n    void operator << (const YAML::Node& node);\n  };\n\n  AckermannCmdSubscribers() : allowed(VACANT) { }\n  ~AckermannCmdSubscribers() { }\n\n  std::vector<AckermannCmdSubs>::size_type size() { return list.size(); };\n  AckermannCmdSubs& operator [] (unsigned int idx) { return list[idx]; };\n\n  /**\n   * @brief Configures the subscribers from a yaml file.\n   *\n   * @exception FileNotFoundException : yaml file not found\n   * @exception YamlException : problem parsing the yaml\n   * @exception EmptyCfgException : empty configuration file\n   * @param node : node holding all the subscriber configuration\n   */\n  void configure(const YAML::Node& node);\n\n  unsigned int allowed;\n\nprivate:\n  std::vector<AckermannCmdSubs> list;\n};\n\n} // namespace ackermann_cmd_mux\n\n#endif /* ACKERMANN_CMD_SUBSCRIBERS_HPP_ */\n"
  },
  {
    "path": "ackermann_cmd_mux/include/ackermann_cmd_mux/exceptions.hpp",
    "content": "/**\n * @file /ackermann_cmd_mux/include/ackermann_cmd_mux/exceptions.hpp\n *\n * @brief Exception classes for ackermann_cmd_mux.\n *\n * License: BSD\n *   https://raw.github.com/yujinrobot/yujin_ocs/hydro/yocs_ackermann_cmd_mux/LICENSE\n **/\n/*****************************************************************************\n** Ifdefs\n*****************************************************************************/\n\n#ifndef RACECAR_ACKERMANN_CMD_EXCEPTIONS_HPP_\n#define RACECAR_ACKERMANN_CMD_EXCEPTIONS_HPP_\n\n/*****************************************************************************\n** Includes\n*****************************************************************************/\n\n#include <exception>\n\n/*****************************************************************************\n** Namespaces\n*****************************************************************************/\n\nnamespace ackermann_cmd_mux {\n\n/*****************************************************************************\n** Exceptions\n*****************************************************************************/\n\nclass FileNotFoundException: public std::runtime_error {\npublic:\n  FileNotFoundException(const std::string& msg)\n        : std::runtime_error(msg) {}\n        virtual ~FileNotFoundException() throw() {}\n};\n\nclass EmptyCfgException: public std::runtime_error {\npublic:\n  EmptyCfgException()\n        : std::runtime_error(\"\") {}\n        virtual ~EmptyCfgException() throw() {}\n};\n\nclass YamlException: public std::runtime_error {\npublic:\n  YamlException(const std::string& msg)\n        : std::runtime_error(msg) {}\n        virtual ~YamlException() throw() {}\n};\n\n} // namespace ackermann_cmd_mux\n\n#endif /* RACECAR_ACKERMANN_CMD_EXCEPTIONS_HPP_ */\n"
  },
  {
    "path": "ackermann_cmd_mux/launch/ackermann_cmd_mux.launch",
    "content": "<!--\n  Ackermann Command Multiplexer launcher\n  -->\n\n<launch>\n  <arg name=\"nodelet_manager_name\"  default=\"nodelet_manager\"/>\n  <arg name=\"config_file\"           default=\"$(find ackermann_cmd_mux)/param/example.yaml\"/>\n\n  <node pkg=\"nodelet\" type=\"nodelet\" name=\"ackermann_cmd_mux\"\n        args=\"load ackermann_cmd_mux/AckermannCmdMuxNodelet $(arg nodelet_manager_name)\">\n    <param name=\"yaml_cfg_file\" value=\"$(arg config_file)\"/>\n  </node>\n</launch>\n"
  },
  {
    "path": "ackermann_cmd_mux/launch/reconfigure.launch",
    "content": "<!--\n  Test the dynamic reconfiguration of the ackermann_cmd_mux. Run this after running the example launcher.\n -->\n<launch>\n  <node name=\"$(anon dynparam)\" pkg=\"dynamic_reconfigure\" type=\"dynparam\" args=\"set_from_parameters nodelet_manager\">\n    <param name=\"yaml_cfg_file\" type=\"string\" value=\"$(find ackermann_cmd_mux)/param/reconfigure.yaml\" />\n  </node>\n</launch>"
  },
  {
    "path": "ackermann_cmd_mux/launch/standalone.launch",
    "content": "<!--\n  Example standalone launcher for the ackermann command multiplexer.\n  \n  For best results you would usually load this into the core control system\n  to avoid latency for reactive controllers. However for other apps, running\n  it standalone with a similar configuration will also work.\n -->\n<launch>\n  <arg name=\"nodelet_manager_name\"  default=\"nodelet_manager\"/>\n  <arg name=\"config_file\"           default=\"$(find ackermann_cmd_mux)/param/example.yaml\"/>\n  \n  <!-- nodelet manager -->\n  <node pkg=\"nodelet\" type=\"nodelet\" name=\"$(arg nodelet_manager_name)\" args=\"manager\"/>\n  \n  <!-- ackermann command mulitplexer -->\n  <include file=\"$(find ackermann_cmd_mux)/launch/ackermann_cmd_mux.launch\">\n    <arg name=\"nodelet_manager_name\"  value=\"$(arg nodelet_manager_name)\"/>\n    <arg name=\"config_file\"           value=\"$(arg config_file)\"/>\n  </include>\n</launch>"
  },
  {
    "path": "ackermann_cmd_mux/package.xml",
    "content": "<package>\n  <name>ackermann_cmd_mux</name>\n  <version>0.7.0</version>\n  <description>\n     A multiplexer for ackermann command velocity inputs. Arbitrates incoming ackermann_cmd messages from\n     several topics, allowing one topic at a time to command the robot, based on priorities. It also\n     deallocates current allowed topic if no messages are received after a configured timeout. All topics,\n     together with their priority and timeout are configured through a YAML file, that can be reload at\n     runtime. Blatantly derived / copied from yujin_ocs/yocs_cmd_vel_mux.\n  </description>\n  <author>Jorge Santos Simon</author>\n  <author>Michael Boulet</author>\n  <maintainer email=\"boulet@ll.mit.edu\">Michael Boulet</maintainer>\n  <license>BSD</license>\n  <url type=\"website\">http://ros.org/wiki/ackermann_cmd_mux</url>\n  <url type=\"repository\">https://github.mit.edu/racecar/racecar</url>\n  <url type=\"bugtracker\">https://github.mit.edu/racecar/racecar/issues</url>\n  \n  <buildtool_depend>catkin</buildtool_depend>\n\n  <build_depend>roscpp</build_depend>\n  <build_depend>nodelet</build_depend>\n  <build_depend>dynamic_reconfigure</build_depend>\n  <build_depend>pluginlib</build_depend>\n  <build_depend>ackermann_msgs</build_depend>\n  <build_depend>yaml-cpp</build_depend>\n  <build_depend>rospy</build_depend>\n  <build_depend>std_msgs</build_depend>\n\n  <run_depend>roscpp</run_depend>\n  <run_depend>ackermann_msgs</run_depend>\n  <run_depend>pluginlib</run_depend>\n  <run_depend>nodelet</run_depend>\n  <run_depend>dynamic_reconfigure</run_depend>\n  <run_depend>yaml-cpp</run_depend>\n  <run_depend>rospy</run_depend>\n  <run_depend>std_msgs</run_depend>\n\n  <export>\n    <nodelet plugin=\"${prefix}/plugins/nodelets.xml\" />\n  </export>\n</package>\n"
  },
  {
    "path": "ackermann_cmd_mux/param/example.yaml",
    "content": "# Created on: Oct 29, 2012\n#     Author: jorge\n# Configuration for subscribers to ackermann_cmd sources. This file is provided just as an example.\n# Typically automatic controllers, as ROS navigation stack should have the minimum priority\n#\n# Used with example.launch\n#\n# Individual subscriber configuration:\n#   name:           Source name\n#   topic:          The topic that provides ackermann_cmd messages\n#   timeout:        Time in seconds without incoming messages to consider this topic inactive\n#   priority:       Priority: an UNIQUE unsigned integer from 0 (lowest) to MAX_INT \n#   short_desc:     Short description (optional)\n\nsubscribers:\n  - name:        \"Default input\"\n    topic:       \"input/default\"\n    timeout:     0.1\n    priority:    0\n    short_desc:  \"The default ackermann_cmd, controllers unaware that we are multiplexing ackermann_cmd should come here\"\n  - name:        \"Navigation stack\"\n    topic:       \"input/navigation\"\n    timeout:     0.5\n    priority:    1\n    short_desc:  \"Navigation stack controller\"\n  - name:        \"Onboard joystick\"\n    topic:       \"input/joystick\"\n    timeout:     0.1\n    priority:    10\n  - name:        \"Remote control\"\n    topic:       \"input/remote\"\n    timeout:     0.1\n    priority:    9\n  - name:        \"Web application\"\n    topic:       \"input/webapp\"\n    timeout:     0.3\n    priority:    8\n  - name:        \"Keyboard operation\"\n    topic:       \"input/keyop\"\n    timeout:     0.1\n    priority:    7\npublisher:       \"output/ackermann_cmd\""
  },
  {
    "path": "ackermann_cmd_mux/param/reconfigure.yaml",
    "content": "# Another example configuration file, though this one is used to test the dynamic reconfiguration\n# of the ackermann_cmd_mux. Used with reconfigure.launch.\n\nsubscribers:\n  - name:        \"Default input\"\n    topic:       \"input/default\"\n    timeout:     0.1\n    priority:    0\n    short_desc:  \"The default ackermann_cmd, controllers unaware that we are multiplexing ackermann_cmd should come here\"\n  - name:        \"Navigation stack\"\n    topic:       \"input/navigation\"\n    timeout:     0.5\n    priority:    1\n    short_desc:  \"Navigation stack controller\"\n  - name:        \"Safety controller\"\n    topic:       \"input/safety\"\n    timeout:     0.1\n    priority:    10\n    short_desc:  \"Used with the reactive velocity control provided by the bumper/cliff sensor safety controller\"\n"
  },
  {
    "path": "ackermann_cmd_mux/plugins/nodelets.xml",
    "content": "<library path=\"lib/libackermann_cmd_mux_nodelet\">\n  <class name=\"ackermann_cmd_mux/AckermannCmdMuxNodelet\"\n         type=\"ackermann_cmd_mux::AckermannCmdMuxNodelet\"\n         base_class_type=\"nodelet::Nodelet\">\n    <description>\n      Implementation for the ackermann command multiplexer as a nodelet.\n    </description>\n  </class>\n</library>\n\n"
  },
  {
    "path": "ackermann_cmd_mux/src/ackermann_cmd_mux_nodelet.cpp",
    "content": "/**\n * @file /src/ackermann_cmd_mux_nodelet.cpp\n *\n * @brief  Implementation for the ackermann command multiplexer\n *\n * License: BSD\n *   https://raw.github.com/yujinrobot/yujin_ocs/hydro/yocs_ackermann_cmd_mux/LICENSE\n **/\n/*****************************************************************************\n ** Includes\n *****************************************************************************/\n\n#include <fstream>\n#include <std_msgs/String.h>\n#include <pluginlib/class_list_macros.h>\n\n#include \"ackermann_cmd_mux/ackermann_cmd_mux_nodelet.hpp\"\n#include \"ackermann_cmd_mux/exceptions.hpp\"\n\n/*****************************************************************************\n** Namespaces\n*****************************************************************************/\n\nnamespace ackermann_cmd_mux {\n\n/*****************************************************************************\n ** Implementation\n *****************************************************************************/\n\nvoid AckermannCmdMuxNodelet::ackermannCmdCallback(const ackermann_msgs::AckermannDriveStamped::ConstPtr& msg, unsigned int idx)\n{\n\t// Reset timer for this source\n\tackermann_cmd_sub[idx].timer.stop();\n\tackermann_cmd_sub[idx].timer.start();\n\n\tackermann_cmd_sub[idx].active = true;   // obviously his source is sending commands, so active\n\n\t// Give permit to publish to this source if it's the only active or is\n\t// already allowed or has higher priority that the currently allowed\n\tif ((ackermann_cmd_sub.allowed == VACANT) ||\n\t\t\t(ackermann_cmd_sub.allowed == idx)    ||\n\t\t\t(ackermann_cmd_sub[idx].priority > ackermann_cmd_sub[ackermann_cmd_sub.allowed].priority))\n\t{\n\t\tif (ackermann_cmd_sub.allowed != idx)\n\t\t{\n\t\t\tackermann_cmd_sub.allowed = idx;\n\n\t\t\t// Notify the world that a new ackermann_cmd source took the control\n\t\t\tstd_msgs::StringPtr acv_msg(new std_msgs::String);\n\t\t\tacv_msg->data = ackermann_cmd_sub[idx].name;\n\t\tif (active_subscriber) {\n\t\t\t\tactive_subscriber.publish(acv_msg);\n\t\t\t}\n\t\t}\n\n\tif (mux_ackermann_cmd_pub){\n\t\t\tmux_ackermann_cmd_pub.publish(msg);\n\t\t}\n\t}\n}\n\nvoid AckermannCmdMuxNodelet::timerCallback(const ros::TimerEvent& event, unsigned int idx)\n{\n\tif (ackermann_cmd_sub.allowed == idx)\n\t{\n\t\t// No ackermann_cmd messages timeout happened to currently active source, so...\n\t\tackermann_cmd_sub.allowed = VACANT;\n\n\t\t// ...notify the world that nobody is publishing on ackermann_cmd; its vacant\n\t\tstd_msgs::StringPtr acv_msg(new std_msgs::String);\n\t\tacv_msg->data = \"idle\";\n\t\tif (active_subscriber){\n\t\t\tactive_subscriber.publish(acv_msg);\n\t\t}\n\t}\n\n\tackermann_cmd_sub[idx].active = false;\n}\n\nvoid AckermannCmdMuxNodelet::onInit()\n{\n\tros::NodeHandle &nh = this->getPrivateNodeHandle();\n\n\t/*********************\n\t** Dynamic Reconfigure\n\t**********************/\n\tdynamic_reconfigure_cb = boost::bind(&AckermannCmdMuxNodelet::reloadConfiguration, this, _1, _2);\n\tdynamic_reconfigure_server = new dynamic_reconfigure::Server<ackermann_cmd_mux::reloadConfig>(nh);\n\tdynamic_reconfigure_server->setCallback(dynamic_reconfigure_cb);\n\n\tactive_subscriber = nh.advertise <std_msgs::String> (\"active\", 1, true); // latched topic\n\n\t// Notify the world that by now nobody is publishing on ackermann_cmd yet\n\tstd_msgs::StringPtr active_msg(new std_msgs::String);\n\tactive_msg->data = \"idle\";\n\tif (active_subscriber) {\n\t\tactive_subscriber.publish(active_msg);\n\t}\n\n\t// could use a call to reloadConfiguration here, but it seems to automatically call it once with defaults anyway.\n\tNODELET_DEBUG(\"AckermannCmdMux : successfully initialised\");\n}\n\nvoid AckermannCmdMuxNodelet::reloadConfiguration(ackermann_cmd_mux::reloadConfig &config, uint32_t unused_level)\n{\n\tstd::string yaml_cfg_file;\n\tros::NodeHandle &nh = this->getNodeHandle();\n\tros::NodeHandle &nh_priv = this->getPrivateNodeHandle();\n\tif( config.yaml_cfg_file == \"\" )\n\t{\n\t\t// typically fired on startup, so look for a parameter to set a default\n\t\tnh_priv.getParam(\"yaml_cfg_file\", yaml_cfg_file);\n\t}\n\telse\n\t{\n\t\tyaml_cfg_file = config.yaml_cfg_file;\n\t}\n\n\t/*********************\n\t** Yaml File Parsing\n\t**********************/\n\tstd::ifstream ifs(yaml_cfg_file.c_str(), std::ifstream::in);\n\tif (ifs.good() == false)\n\t{\n\t\tNODELET_ERROR_STREAM(\"AckermannCmdMux : configuration file not found [\" << yaml_cfg_file << \"]\");\n\t\treturn;\n\t}\n\t// probably need to bring the try catches back here\n\tYAML::Node doc;\n#ifdef HAVE_NEW_YAMLCPP\n\tdoc = YAML::Load(ifs);\n#else\n\tYAML::Parser parser(ifs);\n\tparser.GetNextDocument(doc);\n#endif\n\n\t/*********************\n\t** Output Publisher\n\t**********************/\n\tstd::string output_name(\"output\");\n#ifdef HAVE_NEW_YAMLCPP\n\tif ( doc[\"publisher\"] ) {\n\t\tdoc[\"publisher\"] >> output_name;\n\t}\n#else\n\tconst YAML::Node *node = doc.FindValue(\"publisher\");\n\tif ( node != NULL ) {\n\t\t*node >> output_name;\n\t}\n#endif\n\tmux_ackermann_cmd_pub = nh_priv.advertise <ackermann_msgs::AckermannDriveStamped> (output_name, 10);\n\n\t/*********************\n\t** Input Subscribers\n\t**********************/\n\ttry {\n\t\tackermann_cmd_sub.configure(doc[\"subscribers\"]);\n\t}\n\tcatch(EmptyCfgException& e) {\n\t\tNODELET_WARN(\"AckermannCmdMux : yaml configured zero subscribers, check yaml content.\");\n\t}\n\tcatch(YamlException& e) {\n\t\tNODELET_ERROR_STREAM(\"AckermannCmdMux : yaml parsing problem [\" << std::string(e.what()) + \"]\");\n\t}\n\n\t// Publishers and subscribers\n\tfor (unsigned int i = 0; i < ackermann_cmd_sub.size(); i++)\n\t{\n\t\tackermann_cmd_sub[i].subs =\n\t\t\t\tnh_priv.subscribe<ackermann_msgs::AckermannDriveStamped>(ackermann_cmd_sub[i].topic, 10, AckermannCmdFunctor(i, this));\n\n\t\t// Create (stopped by now) a one-shot timer for every subscriber\n\t\tackermann_cmd_sub[i].timer =\n\t\t\t\tnh_priv.createTimer(ros::Duration(ackermann_cmd_sub[i].timeout), TimerFunctor(i, this), true, false);\n\n\t\tNODELET_DEBUG(\"AckermannCmdMux : subscribed to '%s' on topic '%s'. pr: %d, to: %.2f\",\n\t\t\t\t\t\t\tackermann_cmd_sub[i].name.c_str(), ackermann_cmd_sub[i].topic.c_str(),\n\t\t\t\t\t\t\tackermann_cmd_sub[i].priority, ackermann_cmd_sub[i].timeout);\n\t}\n\n\tNODELET_INFO_STREAM(\"AckermannCmdMux : (re)configured [\" << yaml_cfg_file << \"]\");\n\tifs.close();\n}\n\n} // namespace ackermann_cmd_mux\n\nPLUGINLIB_EXPORT_CLASS(ackermann_cmd_mux::AckermannCmdMuxNodelet, nodelet::Nodelet);\n"
  },
  {
    "path": "ackermann_cmd_mux/src/ackermann_cmd_subscribers.cpp",
    "content": "/**\n * @file /src/ackermann_cmd_subscribers.cpp\n *\n * @brief  Subscriber handlers for the ackermann_cmd_mux\n *\n * License: BSD\n *   https://raw.github.com/yujinrobot/yujin_ocs/hydro/yocs_ackermann_cmd_mux/LICENSE\n **/\n/*****************************************************************************\n ** Includes\n *****************************************************************************/\n\n#include <fstream>\n\n#include \"ackermann_cmd_mux/ackermann_cmd_subscribers.hpp\"\n#include \"ackermann_cmd_mux/exceptions.hpp\"\n\n/*****************************************************************************\n** Namespaces\n*****************************************************************************/\n\nnamespace ackermann_cmd_mux {\n\n/*****************************************************************************\n ** Implementation\n *****************************************************************************/\n\nvoid AckermannCmdSubscribers::AckermannCmdSubs::operator << (const YAML::Node& node)\n{\n  node[\"name\"]       >> name;\n  node[\"topic\"]      >> topic;\n  node[\"timeout\"]    >> timeout;\n  node[\"priority\"]   >> priority;\n#ifdef HAVE_NEW_YAMLCPP\n  if (node[\"short_desc\"]) {\n#else\n  if (node.FindValue(\"short_desc\") != NULL) {\n#endif\n    node[\"short_desc\"] >> short_desc;\n  }\n}\n\nvoid AckermannCmdSubscribers::configure(const YAML::Node& node) {\n\n  list.clear();\n  try\n  {\n    if ( node.size() == 0 ) {\n      throw EmptyCfgException();\n    }\n\n    for (unsigned int i = 0; i < node.size(); i++)\n    {\n      // Parse every entries on YAML\n      AckermannCmdSubs subscriber(i);\n      subscriber << node[i];\n      list.push_back(subscriber);\n    }\n  }\n  catch(EmptyCfgException& e) {\n    throw e;\n  }\n  catch(YAML::ParserException& e)\n  {\n    throw YamlException(e.what());\n  }\n  catch(YAML::RepresentationException& e)\n  {\n    throw YamlException(e.what());\n  }\n}\n\n\n} // namespace ackermann_cmd_mux\n"
  },
  {
    "path": "ackermann_cmd_mux/src/throttle_interpolator.py",
    "content": "#!/usr/bin/env python\nimport rospy\n\nfrom std_msgs.msg import Float64\n\n# import some utils.\nimport numpy as np\nimport copy as copy\n\nclass InterpolateThrottle:\n    def __init__(self):\n\n        # Allow our topics to be dynamic.\n        self.rpm_input_topic   = rospy.get_param('~rpm_input_topic', '/vesc/commands/motor/unsmoothed_speed')\n        self.rpm_output_topic  = rospy.get_param('~rpm_output_topic', '/vesc/commands/motor/speed')\n\n        self.servo_input_topic   = rospy.get_param('~servo_input_topic', '/vesc/commands/servo/unsmoothed_position')\n        self.servo_output_topic  = rospy.get_param('~servo_output_topic', '/vesc/commands/servo/position')\n\n        self.max_acceleration = rospy.get_param('/vesc/max_acceleration')\n        self.max_rpm = rospy.get_param('/vesc/vesc_driver/speed_max')\n        self.min_rpm = rospy.get_param('/vesc/vesc_driver/speed_min')\n        self.throttle_smoother_rate = rospy.get_param('/vesc/throttle_smoother_rate')\n        self.speed_to_erpm_gain = rospy.get_param('/vesc/speed_to_erpm_gain')\n\n        self.max_servo_speed = rospy.get_param('/vesc/max_servo_speed')\n        self.steering_angle_to_servo_gain = rospy.get_param('/vesc/steering_angle_to_servo_gain')\n        self.servo_smoother_rate = rospy.get_param('/vesc/servo_smoother_rate')\n        self.max_servo = rospy.get_param('/vesc/vesc_driver/servo_max')\n        self.min_servo = rospy.get_param('/vesc/vesc_driver/servo_min')\n\n        # Variables\n        self.last_rpm = 0\n        self.desired_rpm = self.last_rpm\n        \n        self.last_servo = rospy.get_param('/vesc/steering_angle_to_servo_offset')\n        self.desired_servo_position = self.last_servo\n\n        # Create topic subscribers and publishers\n        self.rpm_output = rospy.Publisher(self.rpm_output_topic, Float64,queue_size=1)\n        self.servo_output = rospy.Publisher(self.servo_output_topic, Float64,queue_size=1)\n        \n        rospy.Subscriber(self.rpm_input_topic, Float64, self._process_throttle_command)\n        rospy.Subscriber(self.servo_input_topic, Float64, self._process_servo_command)\n\n        self.max_delta_servo = abs(self.steering_angle_to_servo_gain * self.max_servo_speed / self.servo_smoother_rate)\n        rospy.Timer(rospy.Duration(1.0/self.servo_smoother_rate), self._publish_servo_command)\n\n        self.max_delta_rpm = abs(self.speed_to_erpm_gain * self.max_acceleration / self.throttle_smoother_rate)\n        rospy.Timer(rospy.Duration(1.0/self.max_delta_rpm), self._publish_throttle_command)\n        \n        # run the node\n        self._run()\n\n        # Keep the node alive\n    def _run(self):\n        rospy.spin()\n\n    def _publish_throttle_command(self, evt):\n        desired_delta = self.desired_rpm-self.last_rpm\n        clipped_delta = max(min(desired_delta, self.max_delta_rpm), -self.max_delta_rpm)\n        smoothed_rpm = self.last_rpm + clipped_delta\n        self.last_rpm = smoothed_rpm         \n        # print self.desired_rpm, smoothed_rpm\n        self.rpm_output.publish(Float64(smoothed_rpm))\n            \n    def _process_throttle_command(self,msg):\n        input_rpm = msg.data\n        # Do some sanity clipping\n        input_rpm = min(max(input_rpm, self.min_rpm), self.max_rpm)\n        self.desired_rpm = input_rpm\n\n    def _publish_servo_command(self, evt):\n        desired_delta = self.desired_servo_position-self.last_servo\n        clipped_delta = max(min(desired_delta, self.max_delta_servo), -self.max_delta_servo)\n        smoothed_servo = self.last_servo + clipped_delta\n        self.last_servo = smoothed_servo         \n        self.servo_output.publish(Float64(smoothed_servo))\n\n    def _process_servo_command(self,msg):\n        input_servo = msg.data\n        # Do some sanity clipping\n        input_servo = min(max(input_servo, self.min_servo), self.max_servo)\n        # set the target servo position\n        self.desired_servo_position = input_servo\n\n# Boilerplate node spin up. \nif __name__ == '__main__':\n    try:\n        rospy.init_node('Throttle_Interpolator')\n        p = InterpolateThrottle()\n    except rospy.ROSInterruptException:\n        pass\n"
  },
  {
    "path": "racecar/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(racecar)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend and a run_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependencies might have been\n##     pulled in transitively but can be declared for certainty nonetheless:\n##     * add a build_depend tag for \"message_generation\"\n##     * add a run_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs  # Or other packages containing msgs\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if you package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES racecar_launch\n  CATKIN_DEPENDS\n    razor_imu_9dof\n    tf\n    tf2_ros\n    urg_node\n    joy\n    rosbag\n    rostopic\n    rviz\n    # specific to racecar-v1\n    #pointgrey_camera_driver\n    #px4flow\n    #pwm_sysfs_driver\n    # specific to racecar-v2\n    # mapping\n    gmapping\n    hector_mapping\n    robot_pose_ekf\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\n# include_directories(include)\n\n## Declare a cpp library\n# add_library(racecar_launch\n#   src/${PROJECT_NAME}/racecar_launch.cpp\n# )\n\n## Declare a cpp executable\n# add_executable(racecar_launch_node src/racecar_launch_node.cpp)\n\n## Add cmake target dependencies of the executable/library\n## as an example, message headers may need to be generated before nodes\n# add_dependencies(racecar_launch_node racecar_launch_generate_messages_cpp)\n\n## Specify libraries to link a library or executable target against\n# target_link_libraries(racecar_launch_node\n#   ${catkin_LIBRARIES}\n# )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables and/or libraries for installation\n# install(TARGETS racecar_launch racecar_launch_node\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\ninstall(DIRECTORY launch\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_racecar_launch.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "racecar/LICENSE",
    "content": "# Software License Agreement (BSD License)\n#\n# Copyright (c) 2016 Massachusetts Institute of Technology.\n# All rights reserved.\n#\n# Redistribution and use in source and binary forms, with or without\n# modification, are permitted provided that the following conditions\n# are met:\n#\n#    * Redistributions of source code must retain the above copyright\n#        notice, this list of conditions and the following disclaimer.\n#    * Redistributions in binary form must reproduce the above\n#        copyright notice, this list of conditions and the following\n#        disclaimer in the documentation and/or other materials provided\n#        with the distribution.\n#    * Neither the name of Massachusetts Institute of Technology nor the\n#        names of its contributors may be used to endorse or promote\n#        products derived from this software without specific prior\n#        written permission.\n#\n# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n# \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n# POSSIBILITY OF SUCH DAMAGE.\n"
  },
  {
    "path": "racecar/config/racecar-v2/high_level_mux.yaml",
    "content": "# Individual subscriber configuration:\n#   name:           Source name\n#   topic:          The topic that provides ackermann_cmd messages\n#   timeout:        Time in seconds without incoming messages to consider this topic inactive\n#   priority:       Priority: an UNIQUE unsigned integer from 0 (lowest) to MAX_INT \n#   short_desc:     Short description (optional)\n\nsubscribers:\n  - name:        \"Nav_0\"\n    topic:       \"input/nav_0\"\n    timeout:     0.2\n    priority:    20\n    short_desc:  \"Input for autonomous navigation, highest priority\"\n\n  - name:        \"Nav_1\"\n    topic:       \"input/nav_1\"\n    timeout:     0.2\n    priority:    15\n    short_desc:  \"Input for autonomous navigation\"\n\n  - name:        \"Nav_2\"\n    topic:       \"input/nav_2\"\n    timeout:     0.2\n    priority:    10\n    short_desc:  \"Input for autonomous navigation\"\n\n  - name:        \"Nav_3\"\n    topic:       \"input/nav_3\"\n    timeout:     0.2\n    priority:    5\n    short_desc:  \"Input for autonomous navigation\"\n\n  - name:        \"Default\"\n    topic:       \"input/default\"\n    timeout:     1.0\n    priority:    0\n    short_desc:  \"Default input, lowest priority\"\npublisher:       \"output\""
  },
  {
    "path": "racecar/config/racecar-v2/joy_teleop.yaml",
    "content": "joy_node:\n  deadzone: 0.01\n  autorepeat_rate: 20\n  coalesce_interval: 0.01\n\nteleop:\n  # Default mode - Stop for safety\n  default:\n    type: topic\n    is_default: true\n    message_type: ackermann_msgs/AckermannDriveStamped\n    topic_name: low_level/ackermann_cmd_mux/input/teleop\n    message_value:\n      -\n        target: drive.speed\n        value: 0.0\n      -\n        target: drive.steering_angle\n        value: 0.0\n\n  # Enable Human control by holding Left Bumper\n  human_control:\n    type: topic\n    message_type: ackermann_msgs/AckermannDriveStamped\n    topic_name: low_level/ackermann_cmd_mux/input/teleop\n    deadman_buttons: [4]\n    axis_mappings:\n      -\n        axis: 1\n        target: drive.speed\n        scale: 2.0                   # joystick will command plus or minus 2 meters / second\n        offset: 0.0\n      -\n        axis: 3\n        target: drive.steering_angle\n        scale: 0.34                  # joystick will command plus or minus ~20 degrees steering angle\n        offset: 0.0\n\n  # Enable autonomous control by pressing right bumper\n  # This switch causes the joy_teleop to stop sending messages to input/teleop\n  # And send messages to /dev/null (an unused ROS topic)\n  autonomous_control:\n    type: topic\n    message_type: std_msgs/Int8\n    topic_name: /dev/null\n    deadman_buttons: [5]\n    message_value:\n      -\n        target: data\n        value: 0\n"
  },
  {
    "path": "racecar/config/racecar-v2/low_level_mux.yaml",
    "content": "# Individual subscriber configuration:\n#   name:           Source name\n#   topic:          The topic that provides ackermann_cmd messages\n#   timeout:        Time in seconds without incoming messages to consider this topic inactive\n#   priority:       Priority: an UNIQUE unsigned integer from 0 (lowest) to MAX_INT \n#   short_desc:     Short description (optional)\n\nsubscribers:\n  - name:        \"Teleoperation\"\n    topic:       \"input/teleop\"\n    timeout:     0.2\n    priority:    10\n    short_desc:  \"Input for human teleoperation (joystick). Highest priority.\"\n    \n  - name:        \"Safety\"\n    topic:       \"input/safety\"\n    timeout:     0.2\n    priority:    5\n    short_desc:  \"Input for safety monitor.\"\n\n  - name:        \"Navigation\"\n    topic:       \"input/navigation\"\n    timeout:     0.2\n    priority:    0\n    short_desc:  \"Input for autonomous navigation\"\n    \npublisher:       \"output\""
  },
  {
    "path": "racecar/config/racecar-v2/sensors.yaml",
    "content": "\nlaser_node:\n  ip_address: 192.168.0.10\n\nimu_node:\n  device: /dev/imu\n  port: /dev/ttyIMU\n"
  },
  {
    "path": "racecar/config/racecar-v2/vesc.yaml",
    "content": "\n# erpm (electrical rpm) = speed_to_erpm_gain * speed (meters / second) + speed_to_erpm_offset\n# for offset=0. speed_to_erpm_gain = num_motor_poles*60/circumference_wheel_in_meters\nspeed_to_erpm_gain: 4614\nspeed_to_erpm_offset: 0.0\n\ntachometer_ticks_to_meters_gain: 0.00225\n# servo smoother - limits rotation speed and smooths anything above limit\nmax_servo_speed: 3.2 # radians/second\nservo_smoother_rate: 75.0 # messages/sec\n\n# servo smoother - limits acceleration and smooths anything above limit\nmax_acceleration: 3.5 # meters/second^2\nthrottle_smoother_rate: 75.0 # messages/sec\n\n# servo value (0 to 1) =  steering_angle_to_servo_gain * steering angle (radians) + steering_angle_to_servo_offset\nsteering_angle_to_servo_gain: -1.2135\nsteering_angle_to_servo_offset: 0.5304\n\n# publish odom to base link tf\nvesc_to_odom/publish_tf: false\n\n# car wheelbase is about 25cm \nwheelbase: .25\n\nvesc_driver:\n  port: /dev/ttyVESC\n  duty_cycle_min: 0.0\n  duty_cycle_max: 0.0\n  current_min: 0.0\n  current_max: 20.0\n  brake_min: -20000.0\n  brake_max: 200000.0\n  speed_min: -3250\n  speed_max: 10000\n  position_min: 0.0\n  position_max: 0.0\n  servo_min: 0.15\n  servo_max: 0.85\n"
  },
  {
    "path": "racecar/launch/includes/common/joy_teleop.launch.xml",
    "content": "<!-- -*- mode: XML -*- -->\n<launch>\n  <arg name=\"racecar_version\" />\n  <arg name=\"joy_teleop_config\"\n       default=\"$(find racecar)/config/$(arg racecar_version)/joy_teleop.yaml\" />\n\n  <rosparam file=\"$(arg joy_teleop_config)\" command=\"load\" />\n\n  <node pkg=\"joy\" type=\"joy_node\" name=\"joy_node\" />\n\n  <node pkg=\"racecar\" type=\"joy_teleop.py\" name=\"joy_teleop\" />\n\n</launch>\n"
  },
  {
    "path": "racecar/launch/includes/common/sensors.launch.xml",
    "content": "<!-- -*- mode: XML -*- -->\n<launch>\n  <arg name=\"racecar_version\" />\n  <arg name=\"sensors_config\"\n       default=\"$(find racecar)/config/$(arg racecar_version)/sensors.yaml\" />\n\n  <rosparam file=\"$(arg sensors_config)\" command=\"load\" />\n\n  <!-- laser -->\n  <!-- <node pkg=\"urg_node\" type=\"urg_node\" name=\"laser_node\" /> -->\n\n    <!-- export SCANNER_TYPE=hokuyo -->\n  <group if=\"$(eval env('SCANNER_TYPE') == 'hokuyo')\">\n    <!-- Hokoyu laser -->\n    <node pkg=\"urg_node\" type=\"urg_node\" name=\"laser_node\" />\n  </group>\n\n  <!-- export SCANNER_TYPE=velodyne -->\n  <group if=\"$(eval env('SCANNER_TYPE') == 'velodyne')\">\n    <!-- Velodyne 3D laser -->\n    <include file=\"$(find racecar)/launch/includes/racecar-v2/velodyne.launch.xml\">\n      <arg name=\"rpm\" value=\"1200\"/>\n      <arg name=\"max_range\" value=\"30.0\" />\n\n      <!-- this determines which ring to use for the 2D lidar -->\n      <arg name=\"laserscan_ring\" value=\"8\" />\n    </include>\n  </group>\n\n  <!-- imu -->\n  <include file=\"$(find razor_imu_m0_driver)/launch/driver_node.launch\"></include>\n\n</launch>\n"
  },
  {
    "path": "racecar/launch/includes/racecar-v2/static_transforms.launch.xml",
    "content": "<!-- -*- mode: XML -*- -->\n<launch>\n\n  <node pkg=\"tf2_ros\" type=\"static_transform_publisher\" name=\"base_link_to_imu\" \n        args=\"0.245 0.0 0.117    0.7071067811865475 0.7071067811865475 0.0 0.0 /base_link /base_imu_link\" />\n\n  <node pkg=\"tf2_ros\" type=\"static_transform_publisher\" name=\"base_link_to_laser\" \n        args=\"0.285 0.0 0.127 0.0 0.0 0.0 1.0 /base_link /laser\" />\n\n  <node pkg=\"tf2_ros\" type=\"static_transform_publisher\" name=\"base_link_to_base_footprint\" \n        args=\"0.0 0.0 0.0     0.0 0.0 0.0 1.0 /base_link /base_footprint\" />\n\n  <!-- todo: zed camera -->\n  <!-- todo: structure sensor -->\n\n</launch>\n"
  },
  {
    "path": "racecar/launch/includes/racecar-v2/velodyne.launch.xml",
    "content": "<!-- -*- mode: XML -*- -->\n<!-- run velodyne_pointcloud/CloudNodelet in a nodelet manager for a VLP-16 -->\n\n<launch>\n\n  <!-- declare arguments with default values -->\n  <arg name=\"calibration\" default=\"$(find velodyne_pointcloud)/params/VLP16db.yaml\"/>\n  <arg name=\"device_ip\" default=\"\" />\n  <arg name=\"frame_id\" default=\"laser\" />\n  <arg name=\"manager\" default=\"$(arg frame_id)_nodelet_manager\" />\n  <arg name=\"max_range\" default=\"130.0\" />\n  <arg name=\"min_range\" default=\"0.4\" />\n  <arg name=\"pcap\" default=\"\" />\n  <arg name=\"port\" default=\"2368\" />\n  <arg name=\"read_fast\" default=\"false\" />\n  <arg name=\"read_once\" default=\"false\" />\n  <arg name=\"repeat_delay\" default=\"0.0\" />\n  <arg name=\"rpm\" default=\"600.0\" />\n  <arg name=\"laserscan_ring\" default=\"-1\" />\n  <arg name=\"laserscan_resolution\" default=\"0.007\" />\n\n  <!-- start nodelet manager and driver nodelets -->\n  <include file=\"$(find velodyne_driver)/launch/nodelet_manager.launch\">\n    <arg name=\"device_ip\" value=\"$(arg device_ip)\"/>\n    <arg name=\"frame_id\" value=\"$(arg frame_id)\"/>\n    <arg name=\"manager\" value=\"$(arg manager)\" />\n    <arg name=\"model\" value=\"VLP16\"/>\n    <arg name=\"pcap\" value=\"$(arg pcap)\"/>\n    <arg name=\"port\" value=\"$(arg port)\"/>\n    <arg name=\"read_fast\" value=\"$(arg read_fast)\"/>\n    <arg name=\"read_once\" value=\"$(arg read_once)\"/>\n    <arg name=\"repeat_delay\" value=\"$(arg repeat_delay)\"/>\n    <arg name=\"rpm\" value=\"$(arg rpm)\"/>\n  </include>\n\n  <!-- start cloud nodelet -->\n  <include file=\"$(find velodyne_pointcloud)/launch/cloud_nodelet.launch\">\n    <arg name=\"calibration\" value=\"$(arg calibration)\"/>\n    <arg name=\"manager\" value=\"$(arg manager)\" />\n    <arg name=\"max_range\" value=\"$(arg max_range)\"/>\n    <arg name=\"min_range\" value=\"$(arg min_range)\"/>\n  </include>\n\n  <!-- start laserscan nodelet -->\n  <include file=\"$(find velodyne_pointcloud)/launch/laserscan_nodelet.launch\">\n    <arg name=\"manager\" value=\"$(arg manager)\" />\n    <arg name=\"ring\" value=\"$(arg laserscan_ring)\"/>\n    <arg name=\"resolution\" value=\"$(arg laserscan_resolution)\"/>\n  </include>\n\n</launch>\n"
  },
  {
    "path": "racecar/launch/includes/racecar-v2/vesc.launch.xml",
    "content": "<!-- -*- mode: XML -*- -->\n<launch>\n  <arg name=\"racecar_version\" />\n\n  <arg name=\"vesc_config\" default=\"$(find racecar)/config/$(arg racecar_version)/vesc.yaml\" />\n  <rosparam file=\"$(arg vesc_config)\" command=\"load\" />\n\n  <node pkg=\"vesc_ackermann\" type=\"ackermann_to_vesc_node\" name=\"ackermann_to_vesc\">\n    <!-- Remap to make mux control work with the VESC -->\n    <remap from=\"ackermann_cmd\" to=\"low_level/ackermann_cmd_mux/output\" />\n    <!-- Remap to make vesc have trapezoidal control on the throttle to avoid skipping -->\n    <remap from=\"commands/motor/speed\" to=\"commands/motor/unsmoothed_speed\" />\n    <!-- Remap to make vesc have trapezoidal control on the servo to avoid incorrect odometry and damange -->\n    <remap from=\"commands/servo/position\" to=\"commands/servo/unsmoothed_position\" />\n  </node>\n\n  <node pkg=\"vesc_driver\" type=\"vesc_driver_node\" name=\"vesc_driver\" />\n  <node pkg=\"vesc_ackermann\" type=\"vesc_to_odom_node\" name=\"vesc_to_odom\" />\n  <node name=\"throttle_interpolator\" pkg=\"ackermann_cmd_mux\" type=\"throttle_interpolator.py\" />\n\n</launch>\n"
  },
  {
    "path": "racecar/launch/includes/racecar-v2-teleop.launch.xml",
    "content": "<!-- -*- mode: XML -*- -->\n<launch>\n  <arg name=\"racecar_version\" default=\"racecar-v2\" />\n  <arg name=\"run_camera\" default=\"false\"/>\n\n  <group ns=\"vesc\">\n    <!-- joystick node -->\n    <include file=\"$(find racecar)/launch/includes/common/joy_teleop.launch.xml\" >\n      <arg name=\"racecar_version\" value=\"$(arg racecar_version)\" />\n    </include>\n\n    <!-- Spawn MUXs -->\n    <include file=\"$(find racecar)/launch/mux.launch\" />\n\n    <!-- start electronic speed controller driver -->\n    <include file=\"$(find racecar)/launch/includes/$(arg racecar_version)/vesc.launch.xml\" >\n      <arg name=\"racecar_version\" value=\"$(arg racecar_version)\" />\n    </include>\n  </group>\n\n  <!-- start imu and laser scanner -->\n  <include file=\"$(find racecar)/launch/includes/common/sensors.launch.xml\" >\n    <arg name=\"racecar_version\" value=\"$(arg racecar_version)\" />\n  </include>\n\n  <!-- static transforms, e.g. base_link to imu -->\n  <include file=\"$(find racecar)/launch/includes/$(arg racecar_version)/static_transforms.launch.xml\" />\n\n</launch>\n"
  },
  {
    "path": "racecar/launch/known_map_localization.launch",
    "content": "<launch>\n\n  <!-- known map server -->\n  <arg name=\"map\"            default=\"$(find racecar)/maps/short-course-33.yml\" />\n  <node name=\"map_server\" pkg=\"map_server\" type=\"map_server\" args=\"$(arg map)\" />\n\n  <!-- amcl -->\n  <arg name=\"use_map_topic\"  default=\"false\"/>\n  <arg name=\"scan_topic\"     default=\"scan\"/>\n  <arg name=\"initial_pose_x\" default=\"0.0\"/>\n  <arg name=\"initial_pose_y\" default=\"0.0\"/>\n  <arg name=\"initial_pose_a\" default=\"0.0\"/>\n  <node pkg=\"amcl\" type=\"amcl\" name=\"amcl\">\n    <param name=\"use_map_topic\"             value=\"$(arg use_map_topic)\"/>\n    <param name=\"odom_model_type\"           value=\"diff\"/>\n    <param name=\"odom_alpha5\"               value=\"0.1\"/>\n    <!-- Publish scans from best pose at a max of 4 Hz -->\n    <param name=\"gui_publish_rate\"          value=\"4.0\"/>\n    <param name=\"laser_max_beams\"           value=\"60\"/>\n    <param name=\"laser_max_range\"           value=\"12.0\"/>\n    <param name=\"min_particles\"             value=\"500\"/>\n    <param name=\"max_particles\"             value=\"2000\"/>\n    <param name=\"kld_err\"                   value=\"0.05\"/>\n    <param name=\"kld_z\"                     value=\"0.99\"/>\n    <param name=\"odom_alpha1\"               value=\"0.2\"/>\n    <param name=\"odom_alpha2\"               value=\"0.2\"/>\n    <!-- translation std dev, m -->\n    <param name=\"odom_alpha3\"               value=\"0.2\"/>\n    <param name=\"odom_alpha4\"               value=\"0.2\"/>\n    <param name=\"laser_z_hit\"               value=\"0.5\"/>\n    <param name=\"laser_z_short\"             value=\"0.05\"/>\n    <param name=\"laser_z_max\"               value=\"0.05\"/>\n    <param name=\"laser_z_rand\"              value=\"0.5\"/>\n    <param name=\"laser_sigma_hit\"           value=\"0.2\"/>\n    <param name=\"laser_lambda_short\"        value=\"0.1\"/>\n    <param name=\"laser_model_type\"          value=\"likelihood_field\"/>\n    <!-- <param name=\"laser_model_type\" value=\"beam\"/> -->\n    <param name=\"laser_likelihood_max_dist\" value=\"2.0\"/>\n    <param name=\"update_min_d\"              value=\"0.25\"/>\n    <param name=\"update_min_a\"              value=\"0.2\"/>\n    <param name=\"odom_frame_id\"             value=\"odom\"/>\n    <param name=\"base_frame_id\"             value=\"base_footprint\"/>\n    <param name=\"resample_interval\"         value=\"1\"/>\n    <!-- Increase tolerance because the computer can get quite busy -->\n    <param name=\"transform_tolerance\"       value=\"1.0\"/>\n    <param name=\"recovery_alpha_slow\"       value=\"0.0\"/>\n    <param name=\"recovery_alpha_fast\"       value=\"0.0\"/>\n    <param name=\"initial_pose_x\"            value=\"$(arg initial_pose_x)\"/>\n    <param name=\"initial_pose_y\"            value=\"$(arg initial_pose_y)\"/>\n    <param name=\"initial_pose_a\"            value=\"$(arg initial_pose_a)\"/>\n    <remap from=\"scan\"                      to=\"$(arg scan_topic)\"/>\n  </node>\n\n</launch>\n"
  },
  {
    "path": "racecar/launch/mux.launch",
    "content": "<!-- -*- mode: XML -*- -->\n<!--\n This work is sponsored by the Department of the Air Force under Air Force\n Contract FA8721-05-C-0002. Opinions, interpretations, conclusions, and\n recommendations are those of the author and are not necessarily endorsed by\n the United States Government.\n-->\n\n<launch>\n\n  <arg name=\"racecar_version\" default=\"racecar-v2\" />\n\n  <!-- Chain the MUXs -->\n  <node name=\"mux_chainer\" pkg=\"topic_tools\" type=\"relay\"\n  \targs=\"/vesc/high_level/ackermann_cmd_mux/output /vesc/low_level/ackermann_cmd_mux/input/navigation\" />\n\n\n  <!-- Define mappings for backwards compatibility -->\n  <node name=\"mux_topic_backward_compat_safety\" pkg=\"topic_tools\" type=\"relay\"\n  \targs=\"/vesc/ackermann_cmd_mux/input/safety /vesc/low_level/ackermann_cmd_mux/input/safety\" />\n  <node name=\"mux_topic_backward_compat_teleop\" pkg=\"topic_tools\" type=\"relay\"\n  \targs=\"/vesc/ackermann_cmd_mux/input/teleop /vesc/low_level/ackermann_cmd_mux/input/teleop\" />\n  <node name=\"mux_topic_backward_compat_navigation\" pkg=\"topic_tools\" type=\"relay\"\n  \targs=\"/vesc/ackermann_cmd_mux/input/navigation /vesc/high_level/ackermann_cmd_mux/input/nav_0\" />\n  \n  <!-- default (zero) ackermann command for high level MUX -->\n  <node name=\"zero_ackermann_cmd\" pkg=\"rostopic\" type=\"rostopic\" args=\"pub -r 6 high_level/ackermann_cmd_mux/input/default ackermann_msgs/AckermannDriveStamped '{header: auto, drive: {steering_angle: 0.0, speed: 0.0} }'\" />\n  \n  <!-- High level MUX -->\n  <include file=\"$(find ackermann_cmd_mux)/launch/standalone.launch\" ns=\"high_level\">\n    <arg name=\"nodelet_manager_name\" value=\"ackermann_cmd_mux_nodelet_manager\" />\n    <arg name=\"config_file\" value=\"$(find racecar)/config/$(arg racecar_version)/high_level_mux.yaml\" />\n  </include>\n\n  <!-- Low level MUX -->\n  <include file=\"$(find ackermann_cmd_mux)/launch/standalone.launch\" ns=\"low_level\">\n    <arg name=\"nodelet_manager_name\" value=\"ackermann_cmd_mux_nodelet_manager\" />\n    <arg name=\"config_file\" value=\"$(find racecar)/config/$(arg racecar_version)/low_level_mux.yaml\" />\n  </include>\n\n</launch>\n"
  },
  {
    "path": "racecar/launch/replay_bag_file/replay_bag_file.launch",
    "content": "<!-- -*- mode: XML -*- -->\n<launch>\n  <!-- launch script arguments -->\n  <arg name=\"bag\"/>\n  <arg name=\"rate\" default=\"1.0\"/>\n  <arg name=\"start\" default=\"0.0\"/>\n\n  <!-- bag file player -->\n  <param name=\"/use_sim_time\" value=\"true\"/>\n  <node pkg=\"rosbag\" type=\"play\" name=\"play\" output=\"screen\"\n        args=\"$(arg bag) --start $(arg start) --rate $(arg rate) --clock --delay=10\"/>\n</launch>\n"
  },
  {
    "path": "racecar/launch/replay_bag_file/replay_bag_mapping.launch",
    "content": "<!-- -*- mode: XML -*- -->\n<launch>\n  <!-- launch script arguments -->\n  <arg name=\"bag\"/>\n  <arg name=\"rate\" default=\"1.0\"/>\n  <arg name=\"start\" default=\"0.0\"/>\n  <arg name=\"resolution\" default=\"0.05\"/>\n\n  <include file=\"$(find racecar)/launch/replay_bag_file/replay_bag_file.launch\">\n    <arg name=\"bag\" value=\"$(arg bag)\" />\n    <arg name=\"rate\" value=\"$(arg rate)\" />\n    <arg name=\"start\" value=\"$(arg start)\" />\n  </include>\n\n  <include file=\"$(find racecar)/launch/includes/racecar-v1/static_transforms.launch.xml\" />\n\n  <group ns=\"hector\">\n    <!-- force forward velocity -->\n    <node pkg=\"rostopic\" type=\"rostopic\" name=\"fake_velocity\"\n\t  args=\"pub -r 10 vel geometry_msgs/TwistStamped '{header:  {stamp: now, frame_id: &quot;base_link&quot; }, twist: { linear: {x: 0.8, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0} } }'\"/>\n\n    <node pkg=\"laser_scan_matcher\" type=\"laser_scan_matcher_node\" \n\t  name=\"laser_scan_matcher_node\" output=\"screen\">\n\n      <remap from=\"imu/data\" to=\"/imu\" />\n      <remap from=\"scan\" to=\"/scan\" />\n\n      <param name=\"fixed_frame\" value = \"scan_match\"/>\n      <param name=\"base_frame\" value = \"base_link\"/>\n      <param name=\"use_imu\" value=\"false\" />\n      <param name=\"use_odom\" value=\"false\" />\n      <param name=\"use_vel\" value=\"true\" />\n      <param name=\"use_cloud_input\" value=\"false\" />\n      <param name=\"kf_dist_linear\" value=\"0\" />\n      <param name=\"kf_dist_angular\" value=\"0\" />\n      <param name=\"publish_tf\" value=\"true\"/>\n      <param name=\"publish_pose\" value=\"false\"/>\n      <param name=\"publish_pose_stamped\" value=\"false\"/>\n    </node>\n\n    <node pkg=\"hector_mapping\" type=\"hector_mapping\" name=\"hector_mapping\" output=\"screen\">\n\n      <remap from=\"scan\" to=\"/scan\" />\n\n      <param name=\"base_frame\" value=\"base_link\" />\n      <param name=\"map_frame\" value=\"hector_map\" />\n      <param name=\"odom_frame\" value=\"scan_match\" />\n      <param name=\"tf_map_scanmatch_transform_frame_name\" value=\"hector_scan_match\"/>\n      <param name=\"pub_map_odom_transform\" value=\"true\"/>\n      <param name=\"pub_map_scanmatch_transform\" value=\"true\"/>\n      <param name=\"map_resolution\" value=\"0.025\"/>\n      <param name=\"map_size\" value=\"4096\"/>\n      <param name=\"map_start_x\" value=\"0.5\"/>\n      <param name=\"map_start_y\" value=\"0.5\" />\n      <param name=\"update_factor_free\" value=\"0.4\"/>\n      <param name=\"update_factor_occupied\" value=\"0.99\" />    \n      <param name=\"map_update_distance_thresh\" value=\"0.1\"/>\n      <param name=\"map_update_angle_thresh\" value=\"0.01\" />\n    </node>\n\n  </group>\n\n  <node pkg=\"gmapping\" type=\"slam_gmapping\" name=\"slam_gmapping\" output=\"screen\">\n    <param name=\"base_frame\" value=\"base_link\"/>\n    <param name=\"map_frame\" value=\"gmapping_map\"/>\n    <param name=\"odom_frame\" value=\"hector_map\"/>\n    <param name=\"maxUrange\" value=\"8\"/>\n    <param name=\"maxRange\" value=\"12\"/>\n    <param name=\"particles\" value=\"60\"/>\n    <param name=\"delta\" value=\"$(arg resolution)\"/>\n<!--\n    <param name=\"srr\" value=\".05\"/>\n    <param name=\"srt\" value=\".10\"/>\n    <param name=\"str\" value=\".05\"/>\n    <param name=\"stt\" value=\".10\"/>\n    <param name=\"linearUpdate\" value=\".01\"/>\n    <param name=\"angularUpdate\" value=\".05\"/>    \n    <param name=\"temporalUpdate\" value=\"1\"/>\n    <param name=\"map_udpate_interval\" value=\"1.0\"/>\n    <param name=\"particles\" value=\"30\"/>\n    <param name=\"delta\" value=\"0.1\"/>\n    <param name=\"minimumScore\" value=\"50\"/>\n    <param name=\"iterations\" value=\"10\"/>\n    <param name=\"occ_thresh\" value=\"0.25\"/>\n    <param name=\"srr\" value=\".01\"/>\n    <param name=\"srt\" value=\".02\"/>\n    <param name=\"str\" value=\".01\"/>\n    <param name=\"stt\" value=\".02\"/>\n-->\n  </node>\n\n  <node pkg=\"rviz\" type=\"rviz\" name=\"rviz\" \n        args=\"-d $(find racecar)/rviz/mapping.rviz\" />\n\n</launch>"
  },
  {
    "path": "racecar/launch/replay_bag_file/replay_bag_with_lidar_processing.launch",
    "content": "<!-- -*- mode: XML -*- -->\n<launch>\n  <!-- launch script arguments -->\n  <arg name=\"bag\"/>\n  <arg name=\"rate\" default=\"1.0\"/>\n\n  <include file=\"$(find racecar)/launch/replay_bag_file/replay_bag_file.launch\">\n    <arg name=\"bag\" value=\"$(arg bag)\" />\n    <arg name=\"rate\" value=\"$(arg rate)\" />\n  </include>\n\n  <include file=\"$(find racecar)/launch/includes/racecar-v1/static_transforms.launch.xml\" />\n\n  <node pkg=\"laser_scan_matcher\" type=\"laser_scan_matcher_node\" \n        name=\"laser_scan_matcher_node\" output=\"screen\">\n\n    <remap from=\"imu/data\" to=\"imu\" />\n    <param name=\"use_imu\" value=\"false\" />\n    <param name=\"use_odom\" value=\"false\" />\n    <param name=\"use_vel\" value=\"false\" />\n    <param name=\"kf_dist_linear\" value=\"0\" />\n    <param name=\"kf_dist_angular\" value=\"0\" />\n  </node>\n<!--\n  <node pkg=\"robot_pose_ekf\" type=\"robot_pose_ekf\" name=\"robot_pose_ekf\" output=\"screen\">\n    <remap from=\"imu_data\" to=\"imu\" />\n    <param name=\"odom_used\" value=\"false\" />\n    <param name=\"imu_used\" value=\"true\" />\n    <param name=\"vo_used\" value=\"false\" />\n    <param name=\"gps_used\" value=\"false\" />\n  </node>\n-->\n  <node pkg=\"rviz\" type=\"rviz\" name=\"rviz\" \n        args=\"-d $(find racecar)/rviz/laser_scan_matcher.rviz\" />\n\n</launch>"
  },
  {
    "path": "racecar/launch/teleop.launch",
    "content": "<!-- -*- mode: XML -*- -->\n<launch>\n  <arg name=\"racecar_version\" default=\"racecar-v2\" />\n  <arg name=\"run_camera\" default=\"false\"/>\n\n\n  <include file=\"$(find racecar)/launch/includes/$(arg racecar_version)-teleop.launch.xml\">\n    <arg name=\"racecar_version\" value=\"$(arg racecar_version)\" />\n    <arg name=\"run_camera\" value=\"$(arg run_camera)\" />\n  </include>\n\n</launch>\n"
  },
  {
    "path": "racecar/maps/basement_hallways_10cm.yaml",
    "content": "image: basement_hallways_10cm.png\nresolution: 0.100000\norigin: [-30.000000, -30.000000, 0.000000]\nnegate: 0\noccupied_thresh: 0.65\nfree_thresh: 0.196\n\n"
  },
  {
    "path": "racecar/maps/basement_hallways_5cm.yml",
    "content": "image: basement_hallways_5cm.png\nresolution: 0.050000\norigin: [-30.000000, -30.000000, 0.000000]\nnegate: 0\noccupied_thresh: 0.65\nfree_thresh: 0.196\n\n"
  },
  {
    "path": "racecar/maps/short-course-33.yml",
    "content": "image: short-course-33.png\nresolution: 0.025000\norigin: [-11.50000, -5.000000, -0.090000]\nnegate: 0\noccupied_thresh: 0.65\nfree_thresh: 0.196\n\n"
  },
  {
    "path": "racecar/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package>\n  <name>racecar</name>\n  <version>0.0.1</version>\n  <description>RACECAR launch scripts</description>\n\n  <author>Michael Boulet</author>\n  <maintainer email=\"boulet@ll.mit.edu\">Michael Boulet</maintainer>\n  <license>BSD</license>\n\n  <!-- <url type=\"website\">http://wiki.ros.org/pwm_sysfs_driver</url> -->\n\n  <!-- <author email=\"jane.doe@example.com\">Jane Doe</author> -->\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <!--<build_depend></build_depend>-->\n\n  <run_depend>razor_imu_9dof</run_depend>\n  <run_depend>tf</run_depend>\n  <run_depend>tf2_ros</run_depend>\n  <run_depend>urg_node</run_depend>\n  <run_depend>joy</run_depend>\n  <run_depend>rosbag</run_depend>\n  <run_depend>rostopic</run_depend>\n  <run_depend>rviz</run_depend>\n\n  <!-- specific to racecar-v1 -->\n  <!-- <run_depend>pointgrey_camera_driver</run_depend> -->\n  <!-- <run_depend>px4flow</run_depend> -->\n  <!-- <run_depend>pwm_sysfs_driver</run_depend> -->\n\n  <!-- specific to racecar-v2 -->\n\n  <!-- mapping -->\n  <run_depend>gmapping</run_depend>\n  <run_depend>hector_mapping</run_depend>\n  <run_depend>robot_pose_ekf</run_depend>\n\n  <export>\n  </export>\n</package>\n"
  },
  {
    "path": "racecar/rviz/known_map_localization.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /TF1/Tree1/map1\n        - /TF1/Tree1/map1/odom1\n        - /TF1/Tree1/map1/odom1/base_footprint1\n        - /TF1/Tree1/map1/odom1/base_footprint1/base_link1\n      Splitter Ratio: 0.5\n    Tree Height: 531\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: LaserScan\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.03\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 10\n      Reference Frame: map\n      Value: true\n    - Class: rviz/TF\n      Enabled: false\n      Frame Timeout: 15\n      Frames:\n        All Enabled: false\n        base_footprint:\n          Value: true\n        base_link:\n          Value: false\n        camera_depth_frame:\n          Value: false\n        camera_depth_optical_frame:\n          Value: false\n        camera_link:\n          Value: false\n        camera_rgb_frame:\n          Value: false\n        camera_rgb_optical_frame:\n          Value: false\n        caster_back_link:\n          Value: false\n        caster_front_link:\n          Value: false\n        cliff_sensor_front_link:\n          Value: false\n        cliff_sensor_left_link:\n          Value: false\n        cliff_sensor_right_link:\n          Value: false\n        gyro_link:\n          Value: false\n        map:\n          Value: true\n        odom:\n          Value: true\n        plate_bottom_link:\n          Value: false\n        plate_middle_link:\n          Value: false\n        plate_top_link:\n          Value: false\n        pole_bottom_0_link:\n          Value: false\n        pole_bottom_1_link:\n          Value: false\n        pole_bottom_2_link:\n          Value: false\n        pole_bottom_3_link:\n          Value: false\n        pole_bottom_4_link:\n          Value: false\n        pole_bottom_5_link:\n          Value: false\n        pole_kinect_0_link:\n          Value: false\n        pole_kinect_1_link:\n          Value: false\n        pole_middle_0_link:\n          Value: false\n        pole_middle_1_link:\n          Value: false\n        pole_middle_2_link:\n          Value: false\n        pole_middle_3_link:\n          Value: false\n        pole_top_0_link:\n          Value: false\n        pole_top_1_link:\n          Value: false\n        pole_top_2_link:\n          Value: false\n        pole_top_3_link:\n          Value: false\n        wheel_left_link:\n          Value: false\n        wheel_right_link:\n          Value: false\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: true\n      Show Axes: true\n      Show Names: true\n      Tree:\n        map:\n          odom:\n            base_footprint:\n              base_link:\n                camera_rgb_frame:\n                  camera_depth_frame:\n                    camera_depth_optical_frame:\n                      {}\n                  camera_link:\n                    {}\n                  camera_rgb_optical_frame:\n                    {}\n                caster_back_link:\n                  {}\n                caster_front_link:\n                  {}\n                cliff_sensor_front_link:\n                  {}\n                cliff_sensor_left_link:\n                  {}\n                cliff_sensor_right_link:\n                  {}\n                gyro_link:\n                  {}\n                plate_bottom_link:\n                  {}\n                plate_middle_link:\n                  {}\n                plate_top_link:\n                  {}\n                pole_bottom_0_link:\n                  {}\n                pole_bottom_1_link:\n                  {}\n                pole_bottom_2_link:\n                  {}\n                pole_bottom_3_link:\n                  {}\n                pole_bottom_4_link:\n                  {}\n                pole_bottom_5_link:\n                  {}\n                pole_kinect_0_link:\n                  {}\n                pole_kinect_1_link:\n                  {}\n                pole_middle_0_link:\n                  {}\n                pole_middle_1_link:\n                  {}\n                pole_middle_2_link:\n                  {}\n                pole_middle_3_link:\n                  {}\n                pole_top_0_link:\n                  {}\n                pole_top_1_link:\n                  {}\n                pole_top_2_link:\n                  {}\n                pole_top_3_link:\n                  {}\n                wheel_left_link:\n                  {}\n                wheel_right_link:\n                  {}\n      Update Interval: 0\n      Value: false\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 0; 0\n      Color Transformer: FlatColor\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 4096\n      Min Color: 0; 0; 0\n      Min Intensity: 0\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.03\n      Style: Points\n      Topic: /scan\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Alpha: 0.7\n      Class: rviz/Map\n      Color Scheme: map\n      Draw Behind: false\n      Enabled: true\n      Name: Map\n      Topic: /map\n      Value: true\n    - Arrow Length: 0.2\n      Class: rviz/PoseArray\n      Color: 0; 192; 0\n      Enabled: true\n      Name: Amcl Particles\n      Topic: /particlecloud\n      Value: true\n    - Angle Tolerance: 0.1\n      Class: rviz/Odometry\n      Color: 0; 255; 255\n      Enabled: true\n      Keep: 500\n      Length: 0.1\n      Name: Odometry\n      Position Tolerance: 0.1\n      Topic: /vesc/odom\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Fixed Frame: map\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/MoveCamera\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/Select\n    - Class: rviz/SetInitialPose\n      Topic: /initialpose\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/Measure\n  Value: true\n  Views:\n    Current:\n      Angle: -1.935\n      Class: rviz/TopDownOrtho\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.06\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Name: Current View\n      Near Clip Distance: 0.01\n      Scale: 100.79\n      Target Frame: base_footprint\n      Value: TopDownOrtho (rviz)\n      X: 1.71641\n      Y: 0.715559\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 744\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd000000040000000000000142000002a2fc0200000005fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000002a2000000dd00ffffff000000010000010f000002a2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000028000002a2000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a0000002f600fffffffb0000000800540069006d00650100000000000004500000000000000000000002b8000002a200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1301\n  X: 57\n  Y: -4\n"
  },
  {
    "path": "racecar/rviz/laser_scan_matcher.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /Status1\n        - /Grid1\n        - /LaserScan1\n        - /TF1\n        - /TF1/Frames1\n      Splitter Ratio: 0.5\n    Tree Height: 434\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: LaserScan\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.03\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 10\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Alpha: 0.2\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 0; 0\n      Color Transformer: FlatColor\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 0; 0\n      Max Intensity: 4096\n      Min Color: 0; 0; 0\n      Min Intensity: 0\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.025\n      Style: Flat Squares\n      Topic: /scan\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Class: rviz/TF\n      Enabled: true\n      Frame Timeout: 15\n      Frames:\n        All Enabled: true\n        base_link:\n          Value: true\n        laser:\n          Value: true\n        world:\n          Value: true\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: true\n      Show Axes: true\n      Show Names: true\n      Tree:\n        world:\n          base_link:\n            laser:\n              {}\n      Update Interval: 0\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 0; 0; 0\n    Fixed Frame: world\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Topic: /initialpose\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Angle: 0\n      Class: rviz/TopDownOrtho\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.06\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Name: Current View\n      Near Clip Distance: 0.01\n      Scale: 150\n      Target Frame: <Fixed Frame>\n      Value: TopDownOrtho (rviz)\n      X: 0\n      Y: 0\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 721\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd00000004000000000000013c0000023dfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005300fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000360000023d000000b700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000023dfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007301000000360000023d0000009b00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004000000003efc0100000002fb0000000800540069006d00650100000000000004000000024500fffffffb0000000800540069006d00650100000000000004500000000000000000000001a90000023d00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1024\n  X: -2\n  Y: -2\n"
  },
  {
    "path": "racecar/rviz/mapping.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /Status1\n        - /Map1\n        - /LaserScan1\n      Splitter Ratio: 0.5\n    Tree Height: 565\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: LaserScan\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.03\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 10\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Alpha: 0.7\n      Class: rviz/Map\n      Color Scheme: map\n      Draw Behind: false\n      Enabled: true\n      Name: Map\n      Topic: /map\n      Value: true\n    - Class: rviz/TF\n      Enabled: true\n      Frame Timeout: 15\n      Frames:\n        All Enabled: true\n        base_footprint:\n          Value: true\n        base_imu_link:\n          Value: true\n        base_link:\n          Value: true\n        camera:\n          Value: true\n        gmapping_map:\n          Value: true\n        hector_map:\n          Value: true\n        hector_odom:\n          Value: true\n        hector_scanmatcher_frame:\n          Value: true\n        laser:\n          Value: true\n        px4flow:\n          Value: true\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: true\n      Show Axes: true\n      Show Names: true\n      Tree:\n        gmapping_map:\n          hector_map:\n            hector_odom:\n              base_link:\n                base_footprint:\n                  {}\n                base_imu_link:\n                  {}\n                camera:\n                  {}\n                laser:\n                  {}\n                px4flow:\n                  {}\n            hector_scanmatcher_frame:\n              {}\n      Update Interval: 0\n      Value: true\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 255; 255\n      Color Transformer: Intensity\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 1030\n      Min Color: 0; 0; 0\n      Min Intensity: 370\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.08\n      Style: Flat Squares\n      Topic: /scan\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Fixed Frame: gmapping_map\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Topic: /initialpose\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Angle: 0\n      Class: rviz/TopDownOrtho\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.06\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Name: Current View\n      Near Clip Distance: 0.01\n      Scale: 8.5022\n      Target Frame: <Fixed Frame>\n      Value: TopDownOrtho (rviz)\n      X: -0.8955\n      Y: -15.9022\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 846\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd00000004000000000000013c000002c4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000002c4000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002c4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000028000002c4000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002f600fffffffb0000000800540069006d0065010000000000000450000000000000000000000259000002c400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1200\n  X: 372\n  Y: 50\n"
  },
  {
    "path": "racecar/scripts/joy_teleop.py",
    "content": "#!/usr/bin/env python\nimport importlib\n\nimport rospy\nimport genpy.message\nfrom rospy import ROSException\nimport sensor_msgs.msg\nimport actionlib\nimport rostopic\nimport rosservice\nfrom threading import Thread\nfrom rosservice import ROSServiceException\n\nimport numpy as np\n\nclass JoyTeleopException(Exception):\n    pass\n\n'''\nOriginally from https://github.com/ros-teleop/teleop_tools\nPulled on April 28, 2017.\n\nEdited by Winter Guerra on April 28, 2017 to allow for default actions.\n'''\n\n\nclass JoyTeleop:\n    \"\"\"\n    Generic joystick teleoperation node.\n    Will not start without configuration, has to be stored in 'teleop' parameter.\n    See config/joy_teleop.yaml for an example.\n    \"\"\"\n    def __init__(self):\n        if not rospy.has_param(\"teleop\"):\n            rospy.logfatal(\"no configuration was found, taking node down\")\n            raise JoyTeleopException(\"no config\")\n\n        self.publishers = {}\n        self.al_clients = {}\n        self.srv_clients = {}\n        self.service_types = {}\n        self.message_types = {}\n        self.command_list = {}\n        self.offline_actions = []\n        self.offline_services = []\n\n        self.old_buttons = []\n\n        teleop_cfg = rospy.get_param(\"teleop\")\n\n        for i in teleop_cfg:\n            if i in self.command_list:\n                rospy.logerr(\"command {} was duplicated\".format(i))\n                continue\n            action_type = teleop_cfg[i]['type']\n            self.add_command(i, teleop_cfg[i])\n            if action_type == 'topic':\n                self.register_topic(i, teleop_cfg[i])\n            elif action_type == 'action':\n                self.register_action(i, teleop_cfg[i])\n            elif action_type == 'service':\n                self.register_service(i, teleop_cfg[i])\n            else:\n                rospy.logerr(\"unknown type '%s' for command '%s'\", action_type, i)\n\n        # Don't subscribe until everything has been initialized.\n        rospy.Subscriber('joy', sensor_msgs.msg.Joy, self.joy_callback)\n\n        # Run a low-freq action updater\n        rospy.Timer(rospy.Duration(2.0), self.update_actions)\n\n    def joy_callback(self, data):\n        try:\n            for c in self.command_list:\n                if self.match_command(c, data.buttons):\n                    self.run_command(c, data)\n                    # Only run 1 command at a time\n                    break\n        except JoyTeleopException as e:\n            rospy.logerr(\"error while parsing joystick input: %s\", str(e))\n        self.old_buttons = data.buttons\n\n    def register_topic(self, name, command):\n        \"\"\"Add a topic publisher for a joystick command\"\"\"\n        topic_name = command['topic_name']\n        try:\n            topic_type = self.get_message_type(command['message_type'])\n            self.publishers[topic_name] = rospy.Publisher(topic_name, topic_type, queue_size=1)\n        except JoyTeleopException as e:\n            rospy.logerr(\"could not register topic for command {}: {}\".format(name, str(e)))\n\n    def register_action(self, name, command):\n        \"\"\"Add an action client for a joystick command\"\"\"\n        action_name = command['action_name']\n        try:\n            action_type = self.get_message_type(self.get_action_type(action_name))\n            self.al_clients[action_name] = actionlib.SimpleActionClient(action_name, action_type)\n            if action_name in self.offline_actions:\n                self.offline_actions.remove(action_name)\n        except JoyTeleopException:\n            if action_name not in self.offline_actions:\n                self.offline_actions.append(action_name)\n\n    class AsyncServiceProxy(object):\n        def __init__(self, name, service_class, persistent=True):\n            try:\n                rospy.wait_for_service(name, timeout=2.0)\n            except ROSException:\n                raise JoyTeleopException(\"Service {} is not available\".format(name))\n            self._service_proxy = rospy.ServiceProxy(name, service_class, persistent)\n            self._thread = Thread(target=self._service_proxy, args=[])\n\n        def __del__(self):\n            # try to join our thread - no way I know of to interrupt a service\n            # request\n            if self._thread.is_alive():\n                self._thread.join(1.0)\n\n        def __call__(self, request):\n            if self._thread.is_alive():\n                self._thread.join(0.01)\n                if self._thread.is_alive():\n                    return False\n\n            self._thread = Thread(target=self._service_proxy, args=[request])\n            self._thread.start()\n            return True\n\n    def register_service(self, name, command):\n        \"\"\" Add an AsyncServiceProxy for a joystick command \"\"\"\n        service_name = command['service_name']\n        try:\n            service_type = self.get_service_type(service_name)\n            self.srv_clients[service_name] = self.AsyncServiceProxy(\n                service_name,\n                service_type)\n\n            if service_name in self.offline_services:\n                self.offline_services.remove(service_name)\n        except JoyTeleopException:\n            if service_name not in self.offline_services:\n                self.offline_services.append(service_name)\n\n    def match_command(self, c, buttons):\n        \"\"\"Find a command matching a joystick configuration\"\"\"\n        # Buttons is a vector of the shape [0,1,0,1....\n        # Turn it into a vector of form [1, 3...\n        button_indexes = np.argwhere(buttons).flatten()\n\n        # Check if the pressed buttons match the commands exactly.\n        buttons_match = np.array_equal(self.command_list[c]['buttons'], button_indexes)\n\n        #print button_indexes\n        if buttons_match:\n            return True\n\n        # This might also be a default command.\n        # We need to check if ANY commands match this set of pressed buttons.\n        any_commands_matched = np.any([ np.array_equal(command['buttons'], button_indexes) for name, command in self.command_list.iteritems()])\n\n        # Return the final result.\n        return (buttons_match) or (not any_commands_matched and self.command_list[c]['is_default'])\n\n    def add_command(self, name, command):\n        \"\"\"Add a command to the command list\"\"\"\n        # Check if this is a default command\n        if 'is_default' not in command:\n            command['is_default'] = False\n        \n        if command['type'] == 'topic':\n            if 'deadman_buttons' not in command:\n                command['deadman_buttons'] = []\n            command['buttons'] = command['deadman_buttons']\n        elif command['type'] == 'action':\n            if 'action_goal' not in command:\n                command['action_goal'] = {}\n        elif command['type'] == 'service':\n            if 'service_request' not in command:\n                command['service_request'] = {}\n        self.command_list[name] = command\n\n    def run_command(self, command, joy_state):\n        \"\"\"Run a joystick command\"\"\"\n        cmd = self.command_list[command]\n        if cmd['type'] == 'topic':\n            self.run_topic(command, joy_state)\n        elif cmd['type'] == 'action':\n            if cmd['action_name'] in self.offline_actions:\n                rospy.logerr(\"command {} was not played because the action \"\n                             \"server was unavailable. Trying to reconnect...\"\n                             .format(cmd['action_name']))\n                self.register_action(command, self.command_list[command])\n            else:\n                if joy_state.buttons != self.old_buttons:\n                    self.run_action(command, joy_state)\n        elif cmd['type'] == 'service':\n            if cmd['service_name'] in self.offline_services:\n                rospy.logerr(\"command {} was not played because the service \"\n                             \"server was unavailable. Trying to reconnect...\"\n                             .format(cmd['service_name']))\n                self.register_service(command, self.command_list[command])\n            else:\n                if joy_state.buttons != self.old_buttons:\n                    self.run_service(command, joy_state)\n        else:\n            raise JoyTeleopException('command {} is neither a topic publisher nor an action or service client'\n                                     .format(command))\n\n    def run_topic(self, c, joy_state):\n        cmd = self.command_list[c]\n        msg = self.get_message_type(cmd['message_type'])()\n\n        if 'message_value' in cmd:\n            for param in cmd['message_value']:\n                self.set_member(msg, param['target'], param['value'])\n\n        else:\n            for mapping in cmd['axis_mappings']:\n                if len(joy_state.axes)<=mapping['axis']:\n                  rospy.logerr('Joystick has only {} axes (indexed from 0), but #{} was referenced in config.'.format(len(joy_state.axes), mapping['axis']))\n                  val = 0.0\n                else:\n                  val = joy_state.axes[mapping['axis']] * mapping.get('scale', 1.0) + mapping.get('offset', 0.0)\n\n                self.set_member(msg, mapping['target'], val)\n                \n        self.publishers[cmd['topic_name']].publish(msg)\n\n    def run_action(self, c, joy_state):\n        cmd = self.command_list[c]\n        goal = self.get_message_type(self.get_action_type(cmd['action_name'])[:-6] + 'Goal')()\n        genpy.message.fill_message_args(goal, [cmd['action_goal']])\n        self.al_clients[cmd['action_name']].send_goal(goal)\n\n    def run_service(self, c, joy_state):\n        cmd = self.command_list[c]\n        request = self.get_service_type(cmd['service_name'])._request_class()\n        # should work for requests, too\n        genpy.message.fill_message_args(request, [cmd['service_request']])\n        if not self.srv_clients[cmd['service_name']](request):\n            rospy.loginfo('Not sending new service request for command {} because previous request has not finished'\n                          .format(c))\n\n    def set_member(self, msg, member, value):\n        ml = member.split('.')\n        if len(ml) < 1:\n            return\n        target = msg\n        for i in ml[:-1]:\n            target = getattr(target, i)\n        setattr(target, ml[-1], value)\n\n    def get_message_type(self, type_name):\n        if type_name not in self.message_types:\n            try:\n                package, message = type_name.split('/')\n                mod = importlib.import_module(package + '.msg')\n                self.message_types[type_name] = getattr(mod, message)\n            except ValueError:\n                raise JoyTeleopException(\"message type format error\")\n            except ImportError:\n                raise JoyTeleopException(\"module {} could not be loaded\".format(package))\n            except AttributeError:\n                raise JoyTeleopException(\"message {} could not be loaded from module {}\".format(package, message))\n        return self.message_types[type_name]\n\n    def get_action_type(self, action_name):\n        try:\n            return rostopic._get_topic_type(rospy.resolve_name(action_name) + '/goal')[0][:-4]\n        except TypeError:\n            raise JoyTeleopException(\"could not find action {}\".format(action_name))\n\n    def get_service_type(self, service_name):\n        if service_name not in self.service_types:\n            try:\n                self.service_types[service_name] = rosservice.get_service_class_by_name(service_name)\n            except ROSServiceException, e:\n                raise JoyTeleopException(\"service {} could not be loaded: {}\".format(service_name, str(e)))\n        return self.service_types[service_name]\n\n    def update_actions(self, evt=None):\n        for name, cmd in self.command_list.iteritems():\n            if cmd['type'] != 'action':\n                continue\n            if cmd['action_name'] in self.offline_actions:\n                self.register_action(name, cmd)\n\n\nif __name__ == \"__main__\":\n    try:\n        rospy.init_node('joy_teleop')\n        jt = JoyTeleop()\n        rospy.spin()\n    except JoyTeleopException:\n        pass\n    except rospy.ROSInterruptException:\n        pass\n"
  },
  {
    "path": "racecar-vm.rosinstall",
    "content": "- setup-file: {local-name: /opt/ros/kinetic/setup.sh}\n- git: {local-name: src/racecar,         version: master,        uri: 'https://github.com/mit-racecar/racecar.git'}\n- git: {local-name: src/vesc,            version: master,        uri: 'https://github.com/mit-racecar/vesc.git'}\n- git: {local-name: src/racecar-simulator,            version: master,        uri: 'https://github.com/mit-racecar/racecar-simulator.git'}\n"
  },
  {
    "path": "racecar.rosinstall",
    "content": "- setup-file: {local-name: /opt/ros/kinetic/setup.sh}\n- git: {local-name: src/racecar,         version: master,        uri: 'https://github.com/mit-racecar/racecar.git'}\n- git: {local-name: src/vesc,            version: master,        uri: 'https://github.com/mit-racecar/vesc.git'}\n- git: {local-name: src/zed_wrapper,     version: 6c06bb0a3c32aa2dec4a539e296f6ee1d6937518,        uri: 'https://github.com/stereolabs/zed-ros-wrapper.git'}\n"
  }
]