Full Code of mit-racecar/racecar for AI

master b464bf1f8534 cached
52 files
102.1 KB
28.7k tokens
52 symbols
1 requests
Download .txt
Repository: mit-racecar/racecar
Branch: master
Commit: b464bf1f8534
Files: 52
Total size: 102.1 KB

Directory structure:
gitextract_ho3gnwhp/

├── .gitignore
├── ackermann_cmd_mux/
│   ├── .cproject
│   ├── .gitignore
│   ├── .project
│   ├── .pydevproject
│   ├── .settings/
│   │   └── language.settings.xml
│   ├── CHANGELOG.rst
│   ├── CMakeLists.txt
│   ├── LICENSE
│   ├── cfg/
│   │   └── reload.cfg
│   ├── include/
│   │   └── ackermann_cmd_mux/
│   │       ├── ackermann_cmd_mux_nodelet.hpp
│   │       ├── ackermann_cmd_subscribers.hpp
│   │       └── exceptions.hpp
│   ├── launch/
│   │   ├── ackermann_cmd_mux.launch
│   │   ├── reconfigure.launch
│   │   └── standalone.launch
│   ├── package.xml
│   ├── param/
│   │   ├── example.yaml
│   │   └── reconfigure.yaml
│   ├── plugins/
│   │   └── nodelets.xml
│   └── src/
│       ├── ackermann_cmd_mux_nodelet.cpp
│       ├── ackermann_cmd_subscribers.cpp
│       └── throttle_interpolator.py
├── racecar/
│   ├── CMakeLists.txt
│   ├── LICENSE
│   ├── config/
│   │   └── racecar-v2/
│   │       ├── high_level_mux.yaml
│   │       ├── joy_teleop.yaml
│   │       ├── low_level_mux.yaml
│   │       ├── sensors.yaml
│   │       └── vesc.yaml
│   ├── launch/
│   │   ├── includes/
│   │   │   ├── common/
│   │   │   │   ├── joy_teleop.launch.xml
│   │   │   │   └── sensors.launch.xml
│   │   │   ├── racecar-v2/
│   │   │   │   ├── static_transforms.launch.xml
│   │   │   │   ├── velodyne.launch.xml
│   │   │   │   └── vesc.launch.xml
│   │   │   └── racecar-v2-teleop.launch.xml
│   │   ├── known_map_localization.launch
│   │   ├── mux.launch
│   │   ├── replay_bag_file/
│   │   │   ├── replay_bag_file.launch
│   │   │   ├── replay_bag_mapping.launch
│   │   │   └── replay_bag_with_lidar_processing.launch
│   │   └── teleop.launch
│   ├── maps/
│   │   ├── basement_hallways_10cm.yaml
│   │   ├── basement_hallways_5cm.yml
│   │   └── short-course-33.yml
│   ├── package.xml
│   ├── rviz/
│   │   ├── known_map_localization.rviz
│   │   ├── laser_scan_matcher.rviz
│   │   └── mapping.rviz
│   └── scripts/
│       └── joy_teleop.py
├── racecar-vm.rosinstall
└── racecar.rosinstall

================================================
FILE CONTENTS
================================================

================================================
FILE: .gitignore
================================================
# -*- mode: gitignore; -*-
*~
\#*\#


================================================
FILE: ackermann_cmd_mux/.cproject
================================================
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<?fileVersion 4.0.0?><cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage">
	<storageModule moduleId="org.eclipse.cdt.core.settings">
		<cconfiguration id="cdt.managedbuild.toolchain.gnu.base.1612295671">
			<storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.toolchain.gnu.base.1612295671" moduleId="org.eclipse.cdt.core.settings" name="Default">
				<externalSettings/>
				<extensions>
					<extension id="org.eclipse.cdt.core.GmakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
					<extension id="org.eclipse.cdt.core.CWDLocator" point="org.eclipse.cdt.core.ErrorParser"/>
					<extension id="org.eclipse.cdt.core.GCCErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
					<extension id="org.eclipse.cdt.core.GASErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
					<extension id="org.eclipse.cdt.core.GLDErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
					<extension id="org.eclipse.cdt.core.ELF" point="org.eclipse.cdt.core.BinaryParser"/>
				</extensions>
			</storageModule>
			<storageModule moduleId="cdtBuildSystem" version="4.0.0">
				<configuration buildProperties="" description="" id="cdt.managedbuild.toolchain.gnu.base.1612295671" name="Default" parent="org.eclipse.cdt.build.core.emptycfg">
					<folderInfo id="cdt.managedbuild.toolchain.gnu.base.1612295671.1777191576" name="/" resourcePath="">
						<toolChain id="cdt.managedbuild.toolchain.gnu.base.520406189" name="cdt.managedbuild.toolchain.gnu.base" superClass="cdt.managedbuild.toolchain.gnu.base">
							<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"/>
							<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"/>
							<tool id="cdt.managedbuild.tool.gnu.archiver.base.1304797274" name="GCC Archiver" superClass="cdt.managedbuild.tool.gnu.archiver.base"/>
							<tool id="cdt.managedbuild.tool.gnu.cpp.compiler.base.1243660247" name="GCC C++ Compiler" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.base">
								<inputType id="cdt.managedbuild.tool.gnu.cpp.compiler.input.991921373" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.input"/>
							</tool>
							<tool id="cdt.managedbuild.tool.gnu.c.compiler.base.1000098092" name="GCC C Compiler" superClass="cdt.managedbuild.tool.gnu.c.compiler.base">
								<inputType id="cdt.managedbuild.tool.gnu.c.compiler.input.7779663" superClass="cdt.managedbuild.tool.gnu.c.compiler.input"/>
							</tool>
							<tool id="cdt.managedbuild.tool.gnu.c.linker.base.176134653" name="GCC C Linker" superClass="cdt.managedbuild.tool.gnu.c.linker.base"/>
							<tool id="cdt.managedbuild.tool.gnu.cpp.linker.base.370153349" name="GCC C++ Linker" superClass="cdt.managedbuild.tool.gnu.cpp.linker.base">
								<inputType id="cdt.managedbuild.tool.gnu.cpp.linker.input.494129810" superClass="cdt.managedbuild.tool.gnu.cpp.linker.input">
									<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
									<additionalInput kind="additionalinput" paths="$(LIBS)"/>
								</inputType>
							</tool>
							<tool id="cdt.managedbuild.tool.gnu.assembler.base.1233806798" name="GCC Assembler" superClass="cdt.managedbuild.tool.gnu.assembler.base">
								<inputType id="cdt.managedbuild.tool.gnu.assembler.input.1933798163" superClass="cdt.managedbuild.tool.gnu.assembler.input"/>
							</tool>
						</toolChain>
					</folderInfo>
					<sourceEntries>
						<entry flags="VALUE_WORKSPACE_PATH" kind="sourcePath" name="src"/>
						<entry flags="VALUE_WORKSPACE_PATH" kind="sourcePath" name="include/ackermann_cmd_mux"/>
					</sourceEntries>
				</configuration>
			</storageModule>
			<storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
		</cconfiguration>
	</storageModule>
	<storageModule moduleId="cdtBuildSystem" version="4.0.0">
		<project id="ackermann_cmd_mux.null.53888827" name="ackermann_cmd_mux"/>
	</storageModule>
	<storageModule moduleId="scannerConfiguration">
		<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
		<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">
			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId="org.eclipse.cdt.managedbuilder.core.GCCManagedMakePerProjectProfileC"/>
		</scannerConfigBuildInfo>
		<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">
			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId="org.eclipse.cdt.managedbuilder.core.GCCManagedMakePerProjectProfileCPP"/>
		</scannerConfigBuildInfo>
	</storageModule>
	<storageModule moduleId="refreshScope" versionNumber="2">
		<configuration configurationName="Default">
			<resource resourceType="PROJECT" workspacePath="/ackermann_cmd_mux"/>
		</configuration>
	</storageModule>
	<storageModule moduleId="org.eclipse.cdt.core.LanguageSettingsProviders"/>
</cproject>


================================================
FILE: ackermann_cmd_mux/.gitignore
================================================
/bin
/build
/lib


================================================
FILE: ackermann_cmd_mux/.project
================================================
<?xml version="1.0" encoding="UTF-8"?>
<projectDescription>
	<name>ackermann_cmd_mux</name>
	<comment></comment>
	<projects>
	</projects>
	<buildSpec>
		<buildCommand>
			<name>org.python.pydev.PyDevBuilder</name>
			<arguments>
			</arguments>
		</buildCommand>
		<buildCommand>
			<name>org.eclipse.cdt.managedbuilder.core.genmakebuilder</name>
			<triggers>clean,full,incremental,</triggers>
			<arguments>
				<dictionary>
					<key>?name?</key>
					<value></value>
				</dictionary>
				<dictionary>
					<key>org.eclipse.cdt.make.core.append_environment</key>
					<value>true</value>
				</dictionary>
				<dictionary>
					<key>org.eclipse.cdt.make.core.autoBuildTarget</key>
					<value>all</value>
				</dictionary>
				<dictionary>
					<key>org.eclipse.cdt.make.core.buildArguments</key>
					<value></value>
				</dictionary>
				<dictionary>
					<key>org.eclipse.cdt.make.core.buildCommand</key>
					<value>make</value>
				</dictionary>
				<dictionary>
					<key>org.eclipse.cdt.make.core.cleanBuildTarget</key>
					<value>clean</value>
				</dictionary>
				<dictionary>
					<key>org.eclipse.cdt.make.core.contents</key>
					<value>org.eclipse.cdt.make.core.activeConfigSettings</value>
				</dictionary>
				<dictionary>
					<key>org.eclipse.cdt.make.core.enableAutoBuild</key>
					<value>false</value>
				</dictionary>
				<dictionary>
					<key>org.eclipse.cdt.make.core.enableCleanBuild</key>
					<value>true</value>
				</dictionary>
				<dictionary>
					<key>org.eclipse.cdt.make.core.enableFullBuild</key>
					<value>true</value>
				</dictionary>
				<dictionary>
					<key>org.eclipse.cdt.make.core.fullBuildTarget</key>
					<value>all</value>
				</dictionary>
				<dictionary>
					<key>org.eclipse.cdt.make.core.stopOnError</key>
					<value>true</value>
				</dictionary>
				<dictionary>
					<key>org.eclipse.cdt.make.core.useDefaultBuildCmd</key>
					<value>true</value>
				</dictionary>
			</arguments>
		</buildCommand>
		<buildCommand>
			<name>org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder</name>
			<triggers>full,incremental,</triggers>
			<arguments>
			</arguments>
		</buildCommand>
	</buildSpec>
	<natures>
		<nature>org.eclipse.cdt.core.cnature</nature>
		<nature>org.eclipse.cdt.core.ccnature</nature>
		<nature>org.eclipse.cdt.managedbuilder.core.managedBuildNature</nature>
		<nature>org.eclipse.cdt.managedbuilder.core.ScannerConfigNature</nature>
		<nature>org.python.pydev.pythonNature</nature>
	</natures>
</projectDescription>


================================================
FILE: ackermann_cmd_mux/.pydevproject
================================================
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<?eclipse-pydev version="1.0"?>

<pydev_project>
<pydev_property name="org.python.pydev.PYTHON_PROJECT_INTERPRETER">Default</pydev_property>
<pydev_property name="org.python.pydev.PYTHON_PROJECT_VERSION">python 2.7</pydev_property>
</pydev_project>


================================================
FILE: ackermann_cmd_mux/.settings/language.settings.xml
================================================
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<project>
	<configuration id="cdt.managedbuild.toolchain.gnu.base.1612295671" name="Default">
		<extension point="org.eclipse.cdt.core.LanguageSettingsProvider">
			<provider copy-of="extension" id="org.eclipse.cdt.ui.UserLanguageSettingsProvider"/>
			<provider-reference id="org.eclipse.cdt.core.ReferencedProjectsLanguageSettingsProvider" ref="shared-provider"/>
			<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"/>
			<provider-reference id="org.eclipse.cdt.managedbuilder.core.GCCBuiltinSpecsDetector" ref="shared-provider"/>
			<provider-reference id="org.eclipse.cdt.managedbuilder.core.MBSLanguageSettingsProvider" ref="shared-provider"/>
		</extension>
	</configuration>
</project>


================================================
FILE: ackermann_cmd_mux/CHANGELOG.rst
================================================
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package ackermann_cmd_mux
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.6.3 (2014-12-05)
------------------

0.6.2 (2014-11-30)
------------------
* ackermann_cmd_mux: fixes node handle for output pub
  to keep backwards compatibility
* adds a little launcher restructing for muxer and smoother
* Contributors: Marcus Liebhardt

0.6.0 (2014-07-08)
------------------
* updating package informations. remove email for authors. updating maintainer
* Contributors: Jihoon Lee

0.5.3 (2014-03-24)
------------------
* Added support for YAML-CPP 0.5+.
  The new yaml-cpp API removes the "node >> outputvar;" operator, and
  it has a new way of loading documents. There's no version hint in the
  library's headers, so I'm getting the version number from pkg-config.
  This part of the patch is a port of the ones created by @ktossell for
  map_server and other packages.
  The new yaml-cpp also does not have FindValue.
* Contributors: Scott K Logan

0.5.2 (2013-11-05)
------------------

0.5.1 (2013-10-14)
------------------
* Unify naming politics for binaries and plugins.

0.5.0 (2013-10-11)
------------------
* Renamed as ackermann_cmd_mux.

0.4.1 (2013-10-08)
------------------

0.4.0 (2013-08-29)
------------------
* Add bugtracker and repo info URLs.
* Changelogs at package level.
* License link fixed.

0.3.0 (2013-07-02)
------------------

0.2.3 (2013-04-15)
------------------

0.2.2 (2013-02-10)
------------------

0.2.1 (2013-02-08)
------------------

0.2.0 (2013-02-07)
------------------
* Catkinized.

0.1.3 (2013-01-08)
------------------
* More generous description.

0.1.2 (2013-01-02)
------------------
* Dynamically reconfigurable.
* Upgraded to new groovy plugin formats.
* Add reconfigure launcher and parameter file.
* Add a dynamic reconfigure script to accept a yaml filename.

0.1.1 (2012-12-21)
------------------

0.1.0 (2012-12-05)
------------------
* Initial version.


================================================
FILE: ackermann_cmd_mux/CMakeLists.txt
================================================
cmake_minimum_required(VERSION 2.8.3)
project(ackermann_cmd_mux)
find_package(catkin REQUIRED COMPONENTS 
	roscpp 
	pluginlib 
	nodelet 
	dynamic_reconfigure 
	ackermann_msgs
	std_msgs
	rospy
)

# pkg-config support
find_package(PkgConfig)
pkg_search_module(yaml-cpp REQUIRED yaml-cpp)

if(NOT ${yaml-cpp_VERSION} VERSION_LESS "0.5")
add_definitions(-DHAVE_NEW_YAMLCPP)
endif()

# Dynamic reconfigure support
generate_dynamic_reconfigure_options(cfg/reload.cfg)

catkin_package(
   INCLUDE_DIRS include
   LIBRARIES ${PROJECT_NAME}_nodelet
   CATKIN_DEPENDS roscpp pluginlib nodelet dynamic_reconfigure ackermann_msgs rospy std_msgs
   DEPENDS yaml-cpp
)

include_directories(include ${catkin_INCLUDE_DIRS} ${yaml-cpp_INCLUDE_DIRS})

# Nodelet library
add_library(${PROJECT_NAME}_nodelet src/ackermann_cmd_mux_nodelet.cpp src/ackermann_cmd_subscribers.cpp)
#add_dependencies(${PROJECT_NAME}_nodelet ackermann_msgs)
add_dependencies(${PROJECT_NAME}_nodelet ${PROJECT_NAME}_gencfg)

target_link_libraries(${PROJECT_NAME}_nodelet ${catkin_LIBRARIES} ${yaml-cpp_LIBRARIES})

install(TARGETS ${PROJECT_NAME}_nodelet
        DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
)
install(DIRECTORY include/${PROJECT_NAME}/
        DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
)
install(DIRECTORY plugins
        DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
install(DIRECTORY launch
        DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
install(DIRECTORY param
        DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)


================================================
FILE: ackermann_cmd_mux/LICENSE
================================================
# Software License Agreement (BSD License)
#
# Copyright (c) 2012 Yujin Robot, Daniel Stonier, Jorge Santos
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
#    * Redistributions of source code must retain the above copyright
#        notice, this list of conditions and the following disclaimer.
#    * Redistributions in binary form must reproduce the above
#        copyright notice, this list of conditions and the following
#        disclaimer in the documentation and/or other materials provided
#        with the distribution.
#    * Neither the name of Yujin Robot nor the names of its
#        contributors may be used to endorse or promote products derived
#        from this software without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.


================================================
FILE: ackermann_cmd_mux/cfg/reload.cfg
================================================
#!/usr/bin/env python2

PACKAGE = "ackermann_cmd_mux"

from dynamic_reconfigure.parameter_generator_catkin import *

gen = ParameterGenerator()

gen.add("yaml_cfg_file", str_t, 0, "Pathname to a yaml file for re-configuration of the mux", "")

# Second arg is node name it will run in (doc purposes only), third is generated filename prefix
exit(gen.generate(PACKAGE, "ackermann_cmd_mux_reload", "reload"))


================================================
FILE: ackermann_cmd_mux/include/ackermann_cmd_mux/ackermann_cmd_mux_nodelet.hpp
================================================
/**
 * @file /include/ackermann_cmd_mux/ackermann_cmd_mux_nodelet.hpp
 *
 * @brief Structure for the ackermann_cmd_mux.
 *
 * License: BSD
 *   https://raw.github.com/yujinrobot/yujin_ocs/hydro/yocs_ackermann_cmd_mux/LICENSE
 **/
/*****************************************************************************
 ** Ifdefs
 *****************************************************************************/

#ifndef RACECAR_ACKERMANN_CMD_MUX_HPP_
#define RACECAR_ACKERMANN_CMD_MUX_HPP_

/*****************************************************************************
 ** Includes
 *****************************************************************************/

#include <ros/ros.h>
#include <nodelet/nodelet.h>
#include <dynamic_reconfigure/server.h>

#include "ackermann_cmd_mux/reloadConfig.h"
#include "ackermann_cmd_mux/ackermann_cmd_subscribers.hpp"

/*****************************************************************************
** Namespaces
*****************************************************************************/

namespace ackermann_cmd_mux {

/*****************************************************************************
 ** AckermannCmdMux
 *****************************************************************************/

class AckermannCmdMuxNodelet : public nodelet::Nodelet
{
public:
  virtual void onInit();

  AckermannCmdMuxNodelet()
  {
    dynamic_reconfigure_server = NULL;
  }

  ~AckermannCmdMuxNodelet()
  {
    if (dynamic_reconfigure_server != NULL)
      delete dynamic_reconfigure_server;
  }

private:
  AckermannCmdSubscribers ackermann_cmd_sub; /**< Pool of ackermann_cmd topics subscribers */
  ros::Publisher mux_ackermann_cmd_pub; /**< Multiplexed ackermann command topic */
  ros::Publisher active_subscriber; /**< Currently allowed ackermann_cmd subscriber */

  void timerCallback(const ros::TimerEvent& event, unsigned int idx);
  void ackermannCmdCallback(const ackermann_msgs::AckermannDriveStamped::ConstPtr& msg, unsigned int idx);

  /*********************
  ** Dynamic Reconfigure
  **********************/
  dynamic_reconfigure::Server<ackermann_cmd_mux::reloadConfig> * dynamic_reconfigure_server;
  dynamic_reconfigure::Server<ackermann_cmd_mux::reloadConfig>::CallbackType dynamic_reconfigure_cb;
  void reloadConfiguration(ackermann_cmd_mux::reloadConfig &config, uint32_t unused_level);

  /*********************
   ** Private Classes
   **********************/
  // Functor assigned to each incoming ackermann command topic to bind it to ackermann_cmd callback
  class AckermannCmdFunctor
  {
  private:
    unsigned int idx;
    AckermannCmdMuxNodelet* node;

  public:
    AckermannCmdFunctor(unsigned int idx, AckermannCmdMuxNodelet* node) :
        idx(idx), node(node)
    {
    }

    void operator()(const ackermann_msgs::AckermannDriveStamped::ConstPtr& msg)
    {
      node->ackermannCmdCallback(msg, idx);
    }
  };

  // Functor assigned to each ackermann command messages source to bind it to timer callback
  class TimerFunctor
  {
  private:
    unsigned int idx;
    AckermannCmdMuxNodelet* node;

  public:
    TimerFunctor(unsigned int idx, AckermannCmdMuxNodelet* node) :
        idx(idx), node(node)
    {
    }

    void operator()(const ros::TimerEvent& event)
    {
      node->timerCallback(event, idx);
    }
  };
};

} // namespace ackermann_cmd_mux

#endif /* RACECAR_ACKERMANN_CMD_MUX_HPP_ */


================================================
FILE: ackermann_cmd_mux/include/ackermann_cmd_mux/ackermann_cmd_subscribers.hpp
================================================
/**
 * @file /include/ackermann_cmd_mux/ackermann_cmd_subscribers.hpp
 *
 * @brief Structure for the ackermann_cmd_mux.
 *
 * License: BSD
 *   https://raw.github.com/yujinrobot/yujin_ocs/hydro/yocs_ackermann_cmd_mux/LICENSE
 **/
/*****************************************************************************
** Ifdefs
*****************************************************************************/

#ifndef RACECAR_ACKERMANN_CMD_SUBSCRIBERS_HPP_
#define RACECAR_ACKERMANN_CMD_SUBSCRIBERS_HPP_

/*****************************************************************************
** Includes
*****************************************************************************/

#include <ros/ros.h>
#include <ackermann_msgs/AckermannDriveStamped.h>
#include <yaml-cpp/yaml.h>

#ifdef HAVE_NEW_YAMLCPP
// The >> operator disappeared in yaml-cpp 0.5, so this function is
// added to provide support for code written under the yaml-cpp 0.3 API.
template<typename T>
void operator >> (const YAML::Node& node, T& i)
{
  i = node.as<T>();
}
#endif

/*****************************************************************************
** Preprocessing
*****************************************************************************/

// move to a static const?
#define VACANT  std::numeric_limits<unsigned int>::max()

/*****************************************************************************
** Namespaces
*****************************************************************************/

namespace ackermann_cmd_mux {

/*****************************************************************************
** AckermannCmdSubscribers
*****************************************************************************/

/**
 * Pool of ackermann_cmd topics subscribers
 */
class AckermannCmdSubscribers
{
public:

  /**
   * Inner class describing an individual subscriber to a ackermann_cmd topic
   */
  class AckermannCmdSubs
  {
  public:
    unsigned int           idx;          /**< Index; assigned according to the order on YAML file */
    std::string            name;         /**< Descriptive name */
    ros::Subscriber        subs;         /**< The subscriber itself */
    std::string            topic;        /**< The name of the topic */
    ros::Timer             timer;        /**< No incoming messages timeout */
    double                 timeout;      /**< Timer's timeout, in seconds  */
    unsigned int           priority;     /**< UNIQUE integer from 0 (lowest priority) to MAX_INT */
    std::string            short_desc;   /**< Short description (optional) */
    bool                   active;       /**< Whether this source is active */

    AckermannCmdSubs(unsigned int idx) : idx(idx), active(false) {};

    void operator << (const YAML::Node& node);
  };

  AckermannCmdSubscribers() : allowed(VACANT) { }
  ~AckermannCmdSubscribers() { }

  std::vector<AckermannCmdSubs>::size_type size() { return list.size(); };
  AckermannCmdSubs& operator [] (unsigned int idx) { return list[idx]; };

  /**
   * @brief Configures the subscribers from a yaml file.
   *
   * @exception FileNotFoundException : yaml file not found
   * @exception YamlException : problem parsing the yaml
   * @exception EmptyCfgException : empty configuration file
   * @param node : node holding all the subscriber configuration
   */
  void configure(const YAML::Node& node);

  unsigned int allowed;

private:
  std::vector<AckermannCmdSubs> list;
};

} // namespace ackermann_cmd_mux

#endif /* ACKERMANN_CMD_SUBSCRIBERS_HPP_ */


================================================
FILE: ackermann_cmd_mux/include/ackermann_cmd_mux/exceptions.hpp
================================================
/**
 * @file /ackermann_cmd_mux/include/ackermann_cmd_mux/exceptions.hpp
 *
 * @brief Exception classes for ackermann_cmd_mux.
 *
 * License: BSD
 *   https://raw.github.com/yujinrobot/yujin_ocs/hydro/yocs_ackermann_cmd_mux/LICENSE
 **/
/*****************************************************************************
** Ifdefs
*****************************************************************************/

#ifndef RACECAR_ACKERMANN_CMD_EXCEPTIONS_HPP_
#define RACECAR_ACKERMANN_CMD_EXCEPTIONS_HPP_

/*****************************************************************************
** Includes
*****************************************************************************/

#include <exception>

/*****************************************************************************
** Namespaces
*****************************************************************************/

namespace ackermann_cmd_mux {

/*****************************************************************************
** Exceptions
*****************************************************************************/

class FileNotFoundException: public std::runtime_error {
public:
  FileNotFoundException(const std::string& msg)
        : std::runtime_error(msg) {}
        virtual ~FileNotFoundException() throw() {}
};

class EmptyCfgException: public std::runtime_error {
public:
  EmptyCfgException()
        : std::runtime_error("") {}
        virtual ~EmptyCfgException() throw() {}
};

class YamlException: public std::runtime_error {
public:
  YamlException(const std::string& msg)
        : std::runtime_error(msg) {}
        virtual ~YamlException() throw() {}
};

} // namespace ackermann_cmd_mux

#endif /* RACECAR_ACKERMANN_CMD_EXCEPTIONS_HPP_ */


================================================
FILE: ackermann_cmd_mux/launch/ackermann_cmd_mux.launch
================================================
<!--
  Ackermann Command Multiplexer launcher
  -->

<launch>
  <arg name="nodelet_manager_name"  default="nodelet_manager"/>
  <arg name="config_file"           default="$(find ackermann_cmd_mux)/param/example.yaml"/>

  <node pkg="nodelet" type="nodelet" name="ackermann_cmd_mux"
        args="load ackermann_cmd_mux/AckermannCmdMuxNodelet $(arg nodelet_manager_name)">
    <param name="yaml_cfg_file" value="$(arg config_file)"/>
  </node>
</launch>


================================================
FILE: ackermann_cmd_mux/launch/reconfigure.launch
================================================
<!--
  Test the dynamic reconfiguration of the ackermann_cmd_mux. Run this after running the example launcher.
 -->
<launch>
  <node name="$(anon dynparam)" pkg="dynamic_reconfigure" type="dynparam" args="set_from_parameters nodelet_manager">
    <param name="yaml_cfg_file" type="string" value="$(find ackermann_cmd_mux)/param/reconfigure.yaml" />
  </node>
</launch>

================================================
FILE: ackermann_cmd_mux/launch/standalone.launch
================================================
<!--
  Example standalone launcher for the ackermann command multiplexer.
  
  For best results you would usually load this into the core control system
  to avoid latency for reactive controllers. However for other apps, running
  it standalone with a similar configuration will also work.
 -->
<launch>
  <arg name="nodelet_manager_name"  default="nodelet_manager"/>
  <arg name="config_file"           default="$(find ackermann_cmd_mux)/param/example.yaml"/>
  
  <!-- nodelet manager -->
  <node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager_name)" args="manager"/>
  
  <!-- ackermann command mulitplexer -->
  <include file="$(find ackermann_cmd_mux)/launch/ackermann_cmd_mux.launch">
    <arg name="nodelet_manager_name"  value="$(arg nodelet_manager_name)"/>
    <arg name="config_file"           value="$(arg config_file)"/>
  </include>
</launch>

================================================
FILE: ackermann_cmd_mux/package.xml
================================================
<package>
  <name>ackermann_cmd_mux</name>
  <version>0.7.0</version>
  <description>
     A multiplexer for ackermann command velocity inputs. Arbitrates incoming ackermann_cmd messages from
     several topics, allowing one topic at a time to command the robot, based on priorities. It also
     deallocates current allowed topic if no messages are received after a configured timeout. All topics,
     together with their priority and timeout are configured through a YAML file, that can be reload at
     runtime. Blatantly derived / copied from yujin_ocs/yocs_cmd_vel_mux.
  </description>
  <author>Jorge Santos Simon</author>
  <author>Michael Boulet</author>
  <maintainer email="boulet@ll.mit.edu">Michael Boulet</maintainer>
  <license>BSD</license>
  <url type="website">http://ros.org/wiki/ackermann_cmd_mux</url>
  <url type="repository">https://github.mit.edu/racecar/racecar</url>
  <url type="bugtracker">https://github.mit.edu/racecar/racecar/issues</url>
  
  <buildtool_depend>catkin</buildtool_depend>

  <build_depend>roscpp</build_depend>
  <build_depend>nodelet</build_depend>
  <build_depend>dynamic_reconfigure</build_depend>
  <build_depend>pluginlib</build_depend>
  <build_depend>ackermann_msgs</build_depend>
  <build_depend>yaml-cpp</build_depend>
  <build_depend>rospy</build_depend>
  <build_depend>std_msgs</build_depend>

  <run_depend>roscpp</run_depend>
  <run_depend>ackermann_msgs</run_depend>
  <run_depend>pluginlib</run_depend>
  <run_depend>nodelet</run_depend>
  <run_depend>dynamic_reconfigure</run_depend>
  <run_depend>yaml-cpp</run_depend>
  <run_depend>rospy</run_depend>
  <run_depend>std_msgs</run_depend>

  <export>
    <nodelet plugin="${prefix}/plugins/nodelets.xml" />
  </export>
</package>


================================================
FILE: ackermann_cmd_mux/param/example.yaml
================================================
# Created on: Oct 29, 2012
#     Author: jorge
# Configuration for subscribers to ackermann_cmd sources. This file is provided just as an example.
# Typically automatic controllers, as ROS navigation stack should have the minimum priority
#
# Used with example.launch
#
# Individual subscriber configuration:
#   name:           Source name
#   topic:          The topic that provides ackermann_cmd messages
#   timeout:        Time in seconds without incoming messages to consider this topic inactive
#   priority:       Priority: an UNIQUE unsigned integer from 0 (lowest) to MAX_INT 
#   short_desc:     Short description (optional)

subscribers:
  - name:        "Default input"
    topic:       "input/default"
    timeout:     0.1
    priority:    0
    short_desc:  "The default ackermann_cmd, controllers unaware that we are multiplexing ackermann_cmd should come here"
  - name:        "Navigation stack"
    topic:       "input/navigation"
    timeout:     0.5
    priority:    1
    short_desc:  "Navigation stack controller"
  - name:        "Onboard joystick"
    topic:       "input/joystick"
    timeout:     0.1
    priority:    10
  - name:        "Remote control"
    topic:       "input/remote"
    timeout:     0.1
    priority:    9
  - name:        "Web application"
    topic:       "input/webapp"
    timeout:     0.3
    priority:    8
  - name:        "Keyboard operation"
    topic:       "input/keyop"
    timeout:     0.1
    priority:    7
publisher:       "output/ackermann_cmd"

================================================
FILE: ackermann_cmd_mux/param/reconfigure.yaml
================================================
# Another example configuration file, though this one is used to test the dynamic reconfiguration
# of the ackermann_cmd_mux. Used with reconfigure.launch.

subscribers:
  - name:        "Default input"
    topic:       "input/default"
    timeout:     0.1
    priority:    0
    short_desc:  "The default ackermann_cmd, controllers unaware that we are multiplexing ackermann_cmd should come here"
  - name:        "Navigation stack"
    topic:       "input/navigation"
    timeout:     0.5
    priority:    1
    short_desc:  "Navigation stack controller"
  - name:        "Safety controller"
    topic:       "input/safety"
    timeout:     0.1
    priority:    10
    short_desc:  "Used with the reactive velocity control provided by the bumper/cliff sensor safety controller"


================================================
FILE: ackermann_cmd_mux/plugins/nodelets.xml
================================================
<library path="lib/libackermann_cmd_mux_nodelet">
  <class name="ackermann_cmd_mux/AckermannCmdMuxNodelet"
         type="ackermann_cmd_mux::AckermannCmdMuxNodelet"
         base_class_type="nodelet::Nodelet">
    <description>
      Implementation for the ackermann command multiplexer as a nodelet.
    </description>
  </class>
</library>



================================================
FILE: ackermann_cmd_mux/src/ackermann_cmd_mux_nodelet.cpp
================================================
/**
 * @file /src/ackermann_cmd_mux_nodelet.cpp
 *
 * @brief  Implementation for the ackermann command multiplexer
 *
 * License: BSD
 *   https://raw.github.com/yujinrobot/yujin_ocs/hydro/yocs_ackermann_cmd_mux/LICENSE
 **/
/*****************************************************************************
 ** Includes
 *****************************************************************************/

#include <fstream>
#include <std_msgs/String.h>
#include <pluginlib/class_list_macros.h>

#include "ackermann_cmd_mux/ackermann_cmd_mux_nodelet.hpp"
#include "ackermann_cmd_mux/exceptions.hpp"

/*****************************************************************************
** Namespaces
*****************************************************************************/

namespace ackermann_cmd_mux {

/*****************************************************************************
 ** Implementation
 *****************************************************************************/

void AckermannCmdMuxNodelet::ackermannCmdCallback(const ackermann_msgs::AckermannDriveStamped::ConstPtr& msg, unsigned int idx)
{
	// Reset timer for this source
	ackermann_cmd_sub[idx].timer.stop();
	ackermann_cmd_sub[idx].timer.start();

	ackermann_cmd_sub[idx].active = true;   // obviously his source is sending commands, so active

	// Give permit to publish to this source if it's the only active or is
	// already allowed or has higher priority that the currently allowed
	if ((ackermann_cmd_sub.allowed == VACANT) ||
			(ackermann_cmd_sub.allowed == idx)    ||
			(ackermann_cmd_sub[idx].priority > ackermann_cmd_sub[ackermann_cmd_sub.allowed].priority))
	{
		if (ackermann_cmd_sub.allowed != idx)
		{
			ackermann_cmd_sub.allowed = idx;

			// Notify the world that a new ackermann_cmd source took the control
			std_msgs::StringPtr acv_msg(new std_msgs::String);
			acv_msg->data = ackermann_cmd_sub[idx].name;
		if (active_subscriber) {
				active_subscriber.publish(acv_msg);
			}
		}

	if (mux_ackermann_cmd_pub){
			mux_ackermann_cmd_pub.publish(msg);
		}
	}
}

void AckermannCmdMuxNodelet::timerCallback(const ros::TimerEvent& event, unsigned int idx)
{
	if (ackermann_cmd_sub.allowed == idx)
	{
		// No ackermann_cmd messages timeout happened to currently active source, so...
		ackermann_cmd_sub.allowed = VACANT;

		// ...notify the world that nobody is publishing on ackermann_cmd; its vacant
		std_msgs::StringPtr acv_msg(new std_msgs::String);
		acv_msg->data = "idle";
		if (active_subscriber){
			active_subscriber.publish(acv_msg);
		}
	}

	ackermann_cmd_sub[idx].active = false;
}

void AckermannCmdMuxNodelet::onInit()
{
	ros::NodeHandle &nh = this->getPrivateNodeHandle();

	/*********************
	** Dynamic Reconfigure
	**********************/
	dynamic_reconfigure_cb = boost::bind(&AckermannCmdMuxNodelet::reloadConfiguration, this, _1, _2);
	dynamic_reconfigure_server = new dynamic_reconfigure::Server<ackermann_cmd_mux::reloadConfig>(nh);
	dynamic_reconfigure_server->setCallback(dynamic_reconfigure_cb);

	active_subscriber = nh.advertise <std_msgs::String> ("active", 1, true); // latched topic

	// Notify the world that by now nobody is publishing on ackermann_cmd yet
	std_msgs::StringPtr active_msg(new std_msgs::String);
	active_msg->data = "idle";
	if (active_subscriber) {
		active_subscriber.publish(active_msg);
	}

	// could use a call to reloadConfiguration here, but it seems to automatically call it once with defaults anyway.
	NODELET_DEBUG("AckermannCmdMux : successfully initialised");
}

void AckermannCmdMuxNodelet::reloadConfiguration(ackermann_cmd_mux::reloadConfig &config, uint32_t unused_level)
{
	std::string yaml_cfg_file;
	ros::NodeHandle &nh = this->getNodeHandle();
	ros::NodeHandle &nh_priv = this->getPrivateNodeHandle();
	if( config.yaml_cfg_file == "" )
	{
		// typically fired on startup, so look for a parameter to set a default
		nh_priv.getParam("yaml_cfg_file", yaml_cfg_file);
	}
	else
	{
		yaml_cfg_file = config.yaml_cfg_file;
	}

	/*********************
	** Yaml File Parsing
	**********************/
	std::ifstream ifs(yaml_cfg_file.c_str(), std::ifstream::in);
	if (ifs.good() == false)
	{
		NODELET_ERROR_STREAM("AckermannCmdMux : configuration file not found [" << yaml_cfg_file << "]");
		return;
	}
	// probably need to bring the try catches back here
	YAML::Node doc;
#ifdef HAVE_NEW_YAMLCPP
	doc = YAML::Load(ifs);
#else
	YAML::Parser parser(ifs);
	parser.GetNextDocument(doc);
#endif

	/*********************
	** Output Publisher
	**********************/
	std::string output_name("output");
#ifdef HAVE_NEW_YAMLCPP
	if ( doc["publisher"] ) {
		doc["publisher"] >> output_name;
	}
#else
	const YAML::Node *node = doc.FindValue("publisher");
	if ( node != NULL ) {
		*node >> output_name;
	}
#endif
	mux_ackermann_cmd_pub = nh_priv.advertise <ackermann_msgs::AckermannDriveStamped> (output_name, 10);

	/*********************
	** Input Subscribers
	**********************/
	try {
		ackermann_cmd_sub.configure(doc["subscribers"]);
	}
	catch(EmptyCfgException& e) {
		NODELET_WARN("AckermannCmdMux : yaml configured zero subscribers, check yaml content.");
	}
	catch(YamlException& e) {
		NODELET_ERROR_STREAM("AckermannCmdMux : yaml parsing problem [" << std::string(e.what()) + "]");
	}

	// Publishers and subscribers
	for (unsigned int i = 0; i < ackermann_cmd_sub.size(); i++)
	{
		ackermann_cmd_sub[i].subs =
				nh_priv.subscribe<ackermann_msgs::AckermannDriveStamped>(ackermann_cmd_sub[i].topic, 10, AckermannCmdFunctor(i, this));

		// Create (stopped by now) a one-shot timer for every subscriber
		ackermann_cmd_sub[i].timer =
				nh_priv.createTimer(ros::Duration(ackermann_cmd_sub[i].timeout), TimerFunctor(i, this), true, false);

		NODELET_DEBUG("AckermannCmdMux : subscribed to '%s' on topic '%s'. pr: %d, to: %.2f",
							ackermann_cmd_sub[i].name.c_str(), ackermann_cmd_sub[i].topic.c_str(),
							ackermann_cmd_sub[i].priority, ackermann_cmd_sub[i].timeout);
	}

	NODELET_INFO_STREAM("AckermannCmdMux : (re)configured [" << yaml_cfg_file << "]");
	ifs.close();
}

} // namespace ackermann_cmd_mux

PLUGINLIB_EXPORT_CLASS(ackermann_cmd_mux::AckermannCmdMuxNodelet, nodelet::Nodelet);


================================================
FILE: ackermann_cmd_mux/src/ackermann_cmd_subscribers.cpp
================================================
/**
 * @file /src/ackermann_cmd_subscribers.cpp
 *
 * @brief  Subscriber handlers for the ackermann_cmd_mux
 *
 * License: BSD
 *   https://raw.github.com/yujinrobot/yujin_ocs/hydro/yocs_ackermann_cmd_mux/LICENSE
 **/
/*****************************************************************************
 ** Includes
 *****************************************************************************/

#include <fstream>

#include "ackermann_cmd_mux/ackermann_cmd_subscribers.hpp"
#include "ackermann_cmd_mux/exceptions.hpp"

/*****************************************************************************
** Namespaces
*****************************************************************************/

namespace ackermann_cmd_mux {

/*****************************************************************************
 ** Implementation
 *****************************************************************************/

void AckermannCmdSubscribers::AckermannCmdSubs::operator << (const YAML::Node& node)
{
  node["name"]       >> name;
  node["topic"]      >> topic;
  node["timeout"]    >> timeout;
  node["priority"]   >> priority;
#ifdef HAVE_NEW_YAMLCPP
  if (node["short_desc"]) {
#else
  if (node.FindValue("short_desc") != NULL) {
#endif
    node["short_desc"] >> short_desc;
  }
}

void AckermannCmdSubscribers::configure(const YAML::Node& node) {

  list.clear();
  try
  {
    if ( node.size() == 0 ) {
      throw EmptyCfgException();
    }

    for (unsigned int i = 0; i < node.size(); i++)
    {
      // Parse every entries on YAML
      AckermannCmdSubs subscriber(i);
      subscriber << node[i];
      list.push_back(subscriber);
    }
  }
  catch(EmptyCfgException& e) {
    throw e;
  }
  catch(YAML::ParserException& e)
  {
    throw YamlException(e.what());
  }
  catch(YAML::RepresentationException& e)
  {
    throw YamlException(e.what());
  }
}


} // namespace ackermann_cmd_mux


================================================
FILE: ackermann_cmd_mux/src/throttle_interpolator.py
================================================
#!/usr/bin/env python
import rospy

from std_msgs.msg import Float64

# import some utils.
import numpy as np
import copy as copy

class InterpolateThrottle:
    def __init__(self):

        # Allow our topics to be dynamic.
        self.rpm_input_topic   = rospy.get_param('~rpm_input_topic', '/vesc/commands/motor/unsmoothed_speed')
        self.rpm_output_topic  = rospy.get_param('~rpm_output_topic', '/vesc/commands/motor/speed')

        self.servo_input_topic   = rospy.get_param('~servo_input_topic', '/vesc/commands/servo/unsmoothed_position')
        self.servo_output_topic  = rospy.get_param('~servo_output_topic', '/vesc/commands/servo/position')

        self.max_acceleration = rospy.get_param('/vesc/max_acceleration')
        self.max_rpm = rospy.get_param('/vesc/vesc_driver/speed_max')
        self.min_rpm = rospy.get_param('/vesc/vesc_driver/speed_min')
        self.throttle_smoother_rate = rospy.get_param('/vesc/throttle_smoother_rate')
        self.speed_to_erpm_gain = rospy.get_param('/vesc/speed_to_erpm_gain')

        self.max_servo_speed = rospy.get_param('/vesc/max_servo_speed')
        self.steering_angle_to_servo_gain = rospy.get_param('/vesc/steering_angle_to_servo_gain')
        self.servo_smoother_rate = rospy.get_param('/vesc/servo_smoother_rate')
        self.max_servo = rospy.get_param('/vesc/vesc_driver/servo_max')
        self.min_servo = rospy.get_param('/vesc/vesc_driver/servo_min')

        # Variables
        self.last_rpm = 0
        self.desired_rpm = self.last_rpm
        
        self.last_servo = rospy.get_param('/vesc/steering_angle_to_servo_offset')
        self.desired_servo_position = self.last_servo

        # Create topic subscribers and publishers
        self.rpm_output = rospy.Publisher(self.rpm_output_topic, Float64,queue_size=1)
        self.servo_output = rospy.Publisher(self.servo_output_topic, Float64,queue_size=1)
        
        rospy.Subscriber(self.rpm_input_topic, Float64, self._process_throttle_command)
        rospy.Subscriber(self.servo_input_topic, Float64, self._process_servo_command)

        self.max_delta_servo = abs(self.steering_angle_to_servo_gain * self.max_servo_speed / self.servo_smoother_rate)
        rospy.Timer(rospy.Duration(1.0/self.servo_smoother_rate), self._publish_servo_command)

        self.max_delta_rpm = abs(self.speed_to_erpm_gain * self.max_acceleration / self.throttle_smoother_rate)
        rospy.Timer(rospy.Duration(1.0/self.max_delta_rpm), self._publish_throttle_command)
        
        # run the node
        self._run()

        # Keep the node alive
    def _run(self):
        rospy.spin()

    def _publish_throttle_command(self, evt):
        desired_delta = self.desired_rpm-self.last_rpm
        clipped_delta = max(min(desired_delta, self.max_delta_rpm), -self.max_delta_rpm)
        smoothed_rpm = self.last_rpm + clipped_delta
        self.last_rpm = smoothed_rpm         
        # print self.desired_rpm, smoothed_rpm
        self.rpm_output.publish(Float64(smoothed_rpm))
            
    def _process_throttle_command(self,msg):
        input_rpm = msg.data
        # Do some sanity clipping
        input_rpm = min(max(input_rpm, self.min_rpm), self.max_rpm)
        self.desired_rpm = input_rpm

    def _publish_servo_command(self, evt):
        desired_delta = self.desired_servo_position-self.last_servo
        clipped_delta = max(min(desired_delta, self.max_delta_servo), -self.max_delta_servo)
        smoothed_servo = self.last_servo + clipped_delta
        self.last_servo = smoothed_servo         
        self.servo_output.publish(Float64(smoothed_servo))

    def _process_servo_command(self,msg):
        input_servo = msg.data
        # Do some sanity clipping
        input_servo = min(max(input_servo, self.min_servo), self.max_servo)
        # set the target servo position
        self.desired_servo_position = input_servo

# Boilerplate node spin up. 
if __name__ == '__main__':
    try:
        rospy.init_node('Throttle_Interpolator')
        p = InterpolateThrottle()
    except rospy.ROSInterruptException:
        pass


================================================
FILE: racecar/CMakeLists.txt
================================================
cmake_minimum_required(VERSION 2.8.3)
project(racecar)

## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED)

## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)


## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()

################################################
## Declare ROS messages, services and actions ##
################################################

## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
##   * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
##   * If MSG_DEP_SET isn't empty the following dependencies might have been
##     pulled in transitively but can be declared for certainty nonetheless:
##     * add a build_depend tag for "message_generation"
##     * add a run_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
##   * add "message_generation" and every package in MSG_DEP_SET to
##     find_package(catkin REQUIRED COMPONENTS ...)
##   * add "message_runtime" and every package in MSG_DEP_SET to
##     catkin_package(CATKIN_DEPENDS ...)
##   * uncomment the add_*_files sections below as needed
##     and list every .msg/.srv/.action file to be processed
##   * uncomment the generate_messages entry below
##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)

## Generate messages in the 'msg' folder
# add_message_files(
#   FILES
#   Message1.msg
#   Message2.msg
# )

## Generate services in the 'srv' folder
# add_service_files(
#   FILES
#   Service1.srv
#   Service2.srv
# )

## Generate actions in the 'action' folder
# add_action_files(
#   FILES
#   Action1.action
#   Action2.action
# )

## Generate added messages and services with any dependencies listed here
# generate_messages(
#   DEPENDENCIES
#   std_msgs  # Or other packages containing msgs
# )

###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if you package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
#  INCLUDE_DIRS include
#  LIBRARIES racecar_launch
  CATKIN_DEPENDS
    razor_imu_9dof
    tf
    tf2_ros
    urg_node
    joy
    rosbag
    rostopic
    rviz
    # specific to racecar-v1
    #pointgrey_camera_driver
    #px4flow
    #pwm_sysfs_driver
    # specific to racecar-v2
    # mapping
    gmapping
    hector_mapping
    robot_pose_ekf
#  DEPENDS system_lib
)

###########
## Build ##
###########

## Specify additional locations of header files
## Your package locations should be listed before other locations
# include_directories(include)

## Declare a cpp library
# add_library(racecar_launch
#   src/${PROJECT_NAME}/racecar_launch.cpp
# )

## Declare a cpp executable
# add_executable(racecar_launch_node src/racecar_launch_node.cpp)

## Add cmake target dependencies of the executable/library
## as an example, message headers may need to be generated before nodes
# add_dependencies(racecar_launch_node racecar_launch_generate_messages_cpp)

## Specify libraries to link a library or executable target against
# target_link_libraries(racecar_launch_node
#   ${catkin_LIBRARIES}
# )

#############
## Install ##
#############

# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html

## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
#   scripts/my_python_script
#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark executables and/or libraries for installation
# install(TARGETS racecar_launch racecar_launch_node
#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
#   FILES_MATCHING PATTERN "*.h"
#   PATTERN ".svn" EXCLUDE
# )

## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
#   # myfile1
#   # myfile2
#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )

install(DIRECTORY launch
  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

#############
## Testing ##
#############

## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_racecar_launch.cpp)
# if(TARGET ${PROJECT_NAME}-test)
#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()

## Add folders to be run by python nosetests
# catkin_add_nosetests(test)


================================================
FILE: racecar/LICENSE
================================================
# Software License Agreement (BSD License)
#
# Copyright (c) 2016 Massachusetts Institute of Technology.
# All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
#    * Redistributions of source code must retain the above copyright
#        notice, this list of conditions and the following disclaimer.
#    * Redistributions in binary form must reproduce the above
#        copyright notice, this list of conditions and the following
#        disclaimer in the documentation and/or other materials provided
#        with the distribution.
#    * Neither the name of Massachusetts Institute of Technology nor the
#        names of its contributors may be used to endorse or promote
#        products derived from this software without specific prior
#        written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.


================================================
FILE: racecar/config/racecar-v2/high_level_mux.yaml
================================================
# Individual subscriber configuration:
#   name:           Source name
#   topic:          The topic that provides ackermann_cmd messages
#   timeout:        Time in seconds without incoming messages to consider this topic inactive
#   priority:       Priority: an UNIQUE unsigned integer from 0 (lowest) to MAX_INT 
#   short_desc:     Short description (optional)

subscribers:
  - name:        "Nav_0"
    topic:       "input/nav_0"
    timeout:     0.2
    priority:    20
    short_desc:  "Input for autonomous navigation, highest priority"

  - name:        "Nav_1"
    topic:       "input/nav_1"
    timeout:     0.2
    priority:    15
    short_desc:  "Input for autonomous navigation"

  - name:        "Nav_2"
    topic:       "input/nav_2"
    timeout:     0.2
    priority:    10
    short_desc:  "Input for autonomous navigation"

  - name:        "Nav_3"
    topic:       "input/nav_3"
    timeout:     0.2
    priority:    5
    short_desc:  "Input for autonomous navigation"

  - name:        "Default"
    topic:       "input/default"
    timeout:     1.0
    priority:    0
    short_desc:  "Default input, lowest priority"
publisher:       "output"

================================================
FILE: racecar/config/racecar-v2/joy_teleop.yaml
================================================
joy_node:
  deadzone: 0.01
  autorepeat_rate: 20
  coalesce_interval: 0.01

teleop:
  # Default mode - Stop for safety
  default:
    type: topic
    is_default: true
    message_type: ackermann_msgs/AckermannDriveStamped
    topic_name: low_level/ackermann_cmd_mux/input/teleop
    message_value:
      -
        target: drive.speed
        value: 0.0
      -
        target: drive.steering_angle
        value: 0.0

  # Enable Human control by holding Left Bumper
  human_control:
    type: topic
    message_type: ackermann_msgs/AckermannDriveStamped
    topic_name: low_level/ackermann_cmd_mux/input/teleop
    deadman_buttons: [4]
    axis_mappings:
      -
        axis: 1
        target: drive.speed
        scale: 2.0                   # joystick will command plus or minus 2 meters / second
        offset: 0.0
      -
        axis: 3
        target: drive.steering_angle
        scale: 0.34                  # joystick will command plus or minus ~20 degrees steering angle
        offset: 0.0

  # Enable autonomous control by pressing right bumper
  # This switch causes the joy_teleop to stop sending messages to input/teleop
  # And send messages to /dev/null (an unused ROS topic)
  autonomous_control:
    type: topic
    message_type: std_msgs/Int8
    topic_name: /dev/null
    deadman_buttons: [5]
    message_value:
      -
        target: data
        value: 0


================================================
FILE: racecar/config/racecar-v2/low_level_mux.yaml
================================================
# Individual subscriber configuration:
#   name:           Source name
#   topic:          The topic that provides ackermann_cmd messages
#   timeout:        Time in seconds without incoming messages to consider this topic inactive
#   priority:       Priority: an UNIQUE unsigned integer from 0 (lowest) to MAX_INT 
#   short_desc:     Short description (optional)

subscribers:
  - name:        "Teleoperation"
    topic:       "input/teleop"
    timeout:     0.2
    priority:    10
    short_desc:  "Input for human teleoperation (joystick). Highest priority."
    
  - name:        "Safety"
    topic:       "input/safety"
    timeout:     0.2
    priority:    5
    short_desc:  "Input for safety monitor."

  - name:        "Navigation"
    topic:       "input/navigation"
    timeout:     0.2
    priority:    0
    short_desc:  "Input for autonomous navigation"
    
publisher:       "output"

================================================
FILE: racecar/config/racecar-v2/sensors.yaml
================================================

laser_node:
  ip_address: 192.168.0.10

imu_node:
  device: /dev/imu
  port: /dev/ttyIMU


================================================
FILE: racecar/config/racecar-v2/vesc.yaml
================================================

# erpm (electrical rpm) = speed_to_erpm_gain * speed (meters / second) + speed_to_erpm_offset
# for offset=0. speed_to_erpm_gain = num_motor_poles*60/circumference_wheel_in_meters
speed_to_erpm_gain: 4614
speed_to_erpm_offset: 0.0

tachometer_ticks_to_meters_gain: 0.00225
# servo smoother - limits rotation speed and smooths anything above limit
max_servo_speed: 3.2 # radians/second
servo_smoother_rate: 75.0 # messages/sec

# servo smoother - limits acceleration and smooths anything above limit
max_acceleration: 3.5 # meters/second^2
throttle_smoother_rate: 75.0 # messages/sec

# servo value (0 to 1) =  steering_angle_to_servo_gain * steering angle (radians) + steering_angle_to_servo_offset
steering_angle_to_servo_gain: -1.2135
steering_angle_to_servo_offset: 0.5304

# publish odom to base link tf
vesc_to_odom/publish_tf: false

# car wheelbase is about 25cm 
wheelbase: .25

vesc_driver:
  port: /dev/ttyVESC
  duty_cycle_min: 0.0
  duty_cycle_max: 0.0
  current_min: 0.0
  current_max: 20.0
  brake_min: -20000.0
  brake_max: 200000.0
  speed_min: -3250
  speed_max: 10000
  position_min: 0.0
  position_max: 0.0
  servo_min: 0.15
  servo_max: 0.85


================================================
FILE: racecar/launch/includes/common/joy_teleop.launch.xml
================================================
<!-- -*- mode: XML -*- -->
<launch>
  <arg name="racecar_version" />
  <arg name="joy_teleop_config"
       default="$(find racecar)/config/$(arg racecar_version)/joy_teleop.yaml" />

  <rosparam file="$(arg joy_teleop_config)" command="load" />

  <node pkg="joy" type="joy_node" name="joy_node" />

  <node pkg="racecar" type="joy_teleop.py" name="joy_teleop" />

</launch>


================================================
FILE: racecar/launch/includes/common/sensors.launch.xml
================================================
<!-- -*- mode: XML -*- -->
<launch>
  <arg name="racecar_version" />
  <arg name="sensors_config"
       default="$(find racecar)/config/$(arg racecar_version)/sensors.yaml" />

  <rosparam file="$(arg sensors_config)" command="load" />

  <!-- laser -->
  <!-- <node pkg="urg_node" type="urg_node" name="laser_node" /> -->

    <!-- export SCANNER_TYPE=hokuyo -->
  <group if="$(eval env('SCANNER_TYPE') == 'hokuyo')">
    <!-- Hokoyu laser -->
    <node pkg="urg_node" type="urg_node" name="laser_node" />
  </group>

  <!-- export SCANNER_TYPE=velodyne -->
  <group if="$(eval env('SCANNER_TYPE') == 'velodyne')">
    <!-- Velodyne 3D laser -->
    <include file="$(find racecar)/launch/includes/racecar-v2/velodyne.launch.xml">
      <arg name="rpm" value="1200"/>
      <arg name="max_range" value="30.0" />

      <!-- this determines which ring to use for the 2D lidar -->
      <arg name="laserscan_ring" value="8" />
    </include>
  </group>

  <!-- imu -->
  <include file="$(find razor_imu_m0_driver)/launch/driver_node.launch"></include>

</launch>


================================================
FILE: racecar/launch/includes/racecar-v2/static_transforms.launch.xml
================================================
<!-- -*- mode: XML -*- -->
<launch>

  <node pkg="tf2_ros" type="static_transform_publisher" name="base_link_to_imu" 
        args="0.245 0.0 0.117    0.7071067811865475 0.7071067811865475 0.0 0.0 /base_link /base_imu_link" />

  <node pkg="tf2_ros" type="static_transform_publisher" name="base_link_to_laser" 
        args="0.285 0.0 0.127 0.0 0.0 0.0 1.0 /base_link /laser" />

  <node pkg="tf2_ros" type="static_transform_publisher" name="base_link_to_base_footprint" 
        args="0.0 0.0 0.0     0.0 0.0 0.0 1.0 /base_link /base_footprint" />

  <!-- todo: zed camera -->
  <!-- todo: structure sensor -->

</launch>


================================================
FILE: racecar/launch/includes/racecar-v2/velodyne.launch.xml
================================================
<!-- -*- mode: XML -*- -->
<!-- run velodyne_pointcloud/CloudNodelet in a nodelet manager for a VLP-16 -->

<launch>

  <!-- declare arguments with default values -->
  <arg name="calibration" default="$(find velodyne_pointcloud)/params/VLP16db.yaml"/>
  <arg name="device_ip" default="" />
  <arg name="frame_id" default="laser" />
  <arg name="manager" default="$(arg frame_id)_nodelet_manager" />
  <arg name="max_range" default="130.0" />
  <arg name="min_range" default="0.4" />
  <arg name="pcap" default="" />
  <arg name="port" default="2368" />
  <arg name="read_fast" default="false" />
  <arg name="read_once" default="false" />
  <arg name="repeat_delay" default="0.0" />
  <arg name="rpm" default="600.0" />
  <arg name="laserscan_ring" default="-1" />
  <arg name="laserscan_resolution" default="0.007" />

  <!-- start nodelet manager and driver nodelets -->
  <include file="$(find velodyne_driver)/launch/nodelet_manager.launch">
    <arg name="device_ip" value="$(arg device_ip)"/>
    <arg name="frame_id" value="$(arg frame_id)"/>
    <arg name="manager" value="$(arg manager)" />
    <arg name="model" value="VLP16"/>
    <arg name="pcap" value="$(arg pcap)"/>
    <arg name="port" value="$(arg port)"/>
    <arg name="read_fast" value="$(arg read_fast)"/>
    <arg name="read_once" value="$(arg read_once)"/>
    <arg name="repeat_delay" value="$(arg repeat_delay)"/>
    <arg name="rpm" value="$(arg rpm)"/>
  </include>

  <!-- start cloud nodelet -->
  <include file="$(find velodyne_pointcloud)/launch/cloud_nodelet.launch">
    <arg name="calibration" value="$(arg calibration)"/>
    <arg name="manager" value="$(arg manager)" />
    <arg name="max_range" value="$(arg max_range)"/>
    <arg name="min_range" value="$(arg min_range)"/>
  </include>

  <!-- start laserscan nodelet -->
  <include file="$(find velodyne_pointcloud)/launch/laserscan_nodelet.launch">
    <arg name="manager" value="$(arg manager)" />
    <arg name="ring" value="$(arg laserscan_ring)"/>
    <arg name="resolution" value="$(arg laserscan_resolution)"/>
  </include>

</launch>


================================================
FILE: racecar/launch/includes/racecar-v2/vesc.launch.xml
================================================
<!-- -*- mode: XML -*- -->
<launch>
  <arg name="racecar_version" />

  <arg name="vesc_config" default="$(find racecar)/config/$(arg racecar_version)/vesc.yaml" />
  <rosparam file="$(arg vesc_config)" command="load" />

  <node pkg="vesc_ackermann" type="ackermann_to_vesc_node" name="ackermann_to_vesc">
    <!-- Remap to make mux control work with the VESC -->
    <remap from="ackermann_cmd" to="low_level/ackermann_cmd_mux/output" />
    <!-- Remap to make vesc have trapezoidal control on the throttle to avoid skipping -->
    <remap from="commands/motor/speed" to="commands/motor/unsmoothed_speed" />
    <!-- Remap to make vesc have trapezoidal control on the servo to avoid incorrect odometry and damange -->
    <remap from="commands/servo/position" to="commands/servo/unsmoothed_position" />
  </node>

  <node pkg="vesc_driver" type="vesc_driver_node" name="vesc_driver" />
  <node pkg="vesc_ackermann" type="vesc_to_odom_node" name="vesc_to_odom" />
  <node name="throttle_interpolator" pkg="ackermann_cmd_mux" type="throttle_interpolator.py" />

</launch>


================================================
FILE: racecar/launch/includes/racecar-v2-teleop.launch.xml
================================================
<!-- -*- mode: XML -*- -->
<launch>
  <arg name="racecar_version" default="racecar-v2" />
  <arg name="run_camera" default="false"/>

  <group ns="vesc">
    <!-- joystick node -->
    <include file="$(find racecar)/launch/includes/common/joy_teleop.launch.xml" >
      <arg name="racecar_version" value="$(arg racecar_version)" />
    </include>

    <!-- Spawn MUXs -->
    <include file="$(find racecar)/launch/mux.launch" />

    <!-- start electronic speed controller driver -->
    <include file="$(find racecar)/launch/includes/$(arg racecar_version)/vesc.launch.xml" >
      <arg name="racecar_version" value="$(arg racecar_version)" />
    </include>
  </group>

  <!-- start imu and laser scanner -->
  <include file="$(find racecar)/launch/includes/common/sensors.launch.xml" >
    <arg name="racecar_version" value="$(arg racecar_version)" />
  </include>

  <!-- static transforms, e.g. base_link to imu -->
  <include file="$(find racecar)/launch/includes/$(arg racecar_version)/static_transforms.launch.xml" />

</launch>


================================================
FILE: racecar/launch/known_map_localization.launch
================================================
<launch>

  <!-- known map server -->
  <arg name="map"            default="$(find racecar)/maps/short-course-33.yml" />
  <node name="map_server" pkg="map_server" type="map_server" args="$(arg map)" />

  <!-- amcl -->
  <arg name="use_map_topic"  default="false"/>
  <arg name="scan_topic"     default="scan"/>
  <arg name="initial_pose_x" default="0.0"/>
  <arg name="initial_pose_y" default="0.0"/>
  <arg name="initial_pose_a" default="0.0"/>
  <node pkg="amcl" type="amcl" name="amcl">
    <param name="use_map_topic"             value="$(arg use_map_topic)"/>
    <param name="odom_model_type"           value="diff"/>
    <param name="odom_alpha5"               value="0.1"/>
    <!-- Publish scans from best pose at a max of 4 Hz -->
    <param name="gui_publish_rate"          value="4.0"/>
    <param name="laser_max_beams"           value="60"/>
    <param name="laser_max_range"           value="12.0"/>
    <param name="min_particles"             value="500"/>
    <param name="max_particles"             value="2000"/>
    <param name="kld_err"                   value="0.05"/>
    <param name="kld_z"                     value="0.99"/>
    <param name="odom_alpha1"               value="0.2"/>
    <param name="odom_alpha2"               value="0.2"/>
    <!-- translation std dev, m -->
    <param name="odom_alpha3"               value="0.2"/>
    <param name="odom_alpha4"               value="0.2"/>
    <param name="laser_z_hit"               value="0.5"/>
    <param name="laser_z_short"             value="0.05"/>
    <param name="laser_z_max"               value="0.05"/>
    <param name="laser_z_rand"              value="0.5"/>
    <param name="laser_sigma_hit"           value="0.2"/>
    <param name="laser_lambda_short"        value="0.1"/>
    <param name="laser_model_type"          value="likelihood_field"/>
    <!-- <param name="laser_model_type" value="beam"/> -->
    <param name="laser_likelihood_max_dist" value="2.0"/>
    <param name="update_min_d"              value="0.25"/>
    <param name="update_min_a"              value="0.2"/>
    <param name="odom_frame_id"             value="odom"/>
    <param name="base_frame_id"             value="base_footprint"/>
    <param name="resample_interval"         value="1"/>
    <!-- Increase tolerance because the computer can get quite busy -->
    <param name="transform_tolerance"       value="1.0"/>
    <param name="recovery_alpha_slow"       value="0.0"/>
    <param name="recovery_alpha_fast"       value="0.0"/>
    <param name="initial_pose_x"            value="$(arg initial_pose_x)"/>
    <param name="initial_pose_y"            value="$(arg initial_pose_y)"/>
    <param name="initial_pose_a"            value="$(arg initial_pose_a)"/>
    <remap from="scan"                      to="$(arg scan_topic)"/>
  </node>

</launch>


================================================
FILE: racecar/launch/mux.launch
================================================
<!-- -*- mode: XML -*- -->
<!--
 This work is sponsored by the Department of the Air Force under Air Force
 Contract FA8721-05-C-0002. Opinions, interpretations, conclusions, and
 recommendations are those of the author and are not necessarily endorsed by
 the United States Government.
-->

<launch>

  <arg name="racecar_version" default="racecar-v2" />

  <!-- Chain the MUXs -->
  <node name="mux_chainer" pkg="topic_tools" type="relay"
  	args="/vesc/high_level/ackermann_cmd_mux/output /vesc/low_level/ackermann_cmd_mux/input/navigation" />


  <!-- Define mappings for backwards compatibility -->
  <node name="mux_topic_backward_compat_safety" pkg="topic_tools" type="relay"
  	args="/vesc/ackermann_cmd_mux/input/safety /vesc/low_level/ackermann_cmd_mux/input/safety" />
  <node name="mux_topic_backward_compat_teleop" pkg="topic_tools" type="relay"
  	args="/vesc/ackermann_cmd_mux/input/teleop /vesc/low_level/ackermann_cmd_mux/input/teleop" />
  <node name="mux_topic_backward_compat_navigation" pkg="topic_tools" type="relay"
  	args="/vesc/ackermann_cmd_mux/input/navigation /vesc/high_level/ackermann_cmd_mux/input/nav_0" />
  
  <!-- default (zero) ackermann command for high level MUX -->
  <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} }'" />
  
  <!-- High level MUX -->
  <include file="$(find ackermann_cmd_mux)/launch/standalone.launch" ns="high_level">
    <arg name="nodelet_manager_name" value="ackermann_cmd_mux_nodelet_manager" />
    <arg name="config_file" value="$(find racecar)/config/$(arg racecar_version)/high_level_mux.yaml" />
  </include>

  <!-- Low level MUX -->
  <include file="$(find ackermann_cmd_mux)/launch/standalone.launch" ns="low_level">
    <arg name="nodelet_manager_name" value="ackermann_cmd_mux_nodelet_manager" />
    <arg name="config_file" value="$(find racecar)/config/$(arg racecar_version)/low_level_mux.yaml" />
  </include>

</launch>


================================================
FILE: racecar/launch/replay_bag_file/replay_bag_file.launch
================================================
<!-- -*- mode: XML -*- -->
<launch>
  <!-- launch script arguments -->
  <arg name="bag"/>
  <arg name="rate" default="1.0"/>
  <arg name="start" default="0.0"/>

  <!-- bag file player -->
  <param name="/use_sim_time" value="true"/>
  <node pkg="rosbag" type="play" name="play" output="screen"
        args="$(arg bag) --start $(arg start) --rate $(arg rate) --clock --delay=10"/>
</launch>


================================================
FILE: racecar/launch/replay_bag_file/replay_bag_mapping.launch
================================================
<!-- -*- mode: XML -*- -->
<launch>
  <!-- launch script arguments -->
  <arg name="bag"/>
  <arg name="rate" default="1.0"/>
  <arg name="start" default="0.0"/>
  <arg name="resolution" default="0.05"/>

  <include file="$(find racecar)/launch/replay_bag_file/replay_bag_file.launch">
    <arg name="bag" value="$(arg bag)" />
    <arg name="rate" value="$(arg rate)" />
    <arg name="start" value="$(arg start)" />
  </include>

  <include file="$(find racecar)/launch/includes/racecar-v1/static_transforms.launch.xml" />

  <group ns="hector">
    <!-- force forward velocity -->
    <node pkg="rostopic" type="rostopic" name="fake_velocity"
	  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} } }'"/>

    <node pkg="laser_scan_matcher" type="laser_scan_matcher_node" 
	  name="laser_scan_matcher_node" output="screen">

      <remap from="imu/data" to="/imu" />
      <remap from="scan" to="/scan" />

      <param name="fixed_frame" value = "scan_match"/>
      <param name="base_frame" value = "base_link"/>
      <param name="use_imu" value="false" />
      <param name="use_odom" value="false" />
      <param name="use_vel" value="true" />
      <param name="use_cloud_input" value="false" />
      <param name="kf_dist_linear" value="0" />
      <param name="kf_dist_angular" value="0" />
      <param name="publish_tf" value="true"/>
      <param name="publish_pose" value="false"/>
      <param name="publish_pose_stamped" value="false"/>
    </node>

    <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">

      <remap from="scan" to="/scan" />

      <param name="base_frame" value="base_link" />
      <param name="map_frame" value="hector_map" />
      <param name="odom_frame" value="scan_match" />
      <param name="tf_map_scanmatch_transform_frame_name" value="hector_scan_match"/>
      <param name="pub_map_odom_transform" value="true"/>
      <param name="pub_map_scanmatch_transform" value="true"/>
      <param name="map_resolution" value="0.025"/>
      <param name="map_size" value="4096"/>
      <param name="map_start_x" value="0.5"/>
      <param name="map_start_y" value="0.5" />
      <param name="update_factor_free" value="0.4"/>
      <param name="update_factor_occupied" value="0.99" />    
      <param name="map_update_distance_thresh" value="0.1"/>
      <param name="map_update_angle_thresh" value="0.01" />
    </node>

  </group>

  <node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
    <param name="base_frame" value="base_link"/>
    <param name="map_frame" value="gmapping_map"/>
    <param name="odom_frame" value="hector_map"/>
    <param name="maxUrange" value="8"/>
    <param name="maxRange" value="12"/>
    <param name="particles" value="60"/>
    <param name="delta" value="$(arg resolution)"/>
<!--
    <param name="srr" value=".05"/>
    <param name="srt" value=".10"/>
    <param name="str" value=".05"/>
    <param name="stt" value=".10"/>
    <param name="linearUpdate" value=".01"/>
    <param name="angularUpdate" value=".05"/>    
    <param name="temporalUpdate" value="1"/>
    <param name="map_udpate_interval" value="1.0"/>
    <param name="particles" value="30"/>
    <param name="delta" value="0.1"/>
    <param name="minimumScore" value="50"/>
    <param name="iterations" value="10"/>
    <param name="occ_thresh" value="0.25"/>
    <param name="srr" value=".01"/>
    <param name="srt" value=".02"/>
    <param name="str" value=".01"/>
    <param name="stt" value=".02"/>
-->
  </node>

  <node pkg="rviz" type="rviz" name="rviz" 
        args="-d $(find racecar)/rviz/mapping.rviz" />

</launch>

================================================
FILE: racecar/launch/replay_bag_file/replay_bag_with_lidar_processing.launch
================================================
<!-- -*- mode: XML -*- -->
<launch>
  <!-- launch script arguments -->
  <arg name="bag"/>
  <arg name="rate" default="1.0"/>

  <include file="$(find racecar)/launch/replay_bag_file/replay_bag_file.launch">
    <arg name="bag" value="$(arg bag)" />
    <arg name="rate" value="$(arg rate)" />
  </include>

  <include file="$(find racecar)/launch/includes/racecar-v1/static_transforms.launch.xml" />

  <node pkg="laser_scan_matcher" type="laser_scan_matcher_node" 
        name="laser_scan_matcher_node" output="screen">

    <remap from="imu/data" to="imu" />
    <param name="use_imu" value="false" />
    <param name="use_odom" value="false" />
    <param name="use_vel" value="false" />
    <param name="kf_dist_linear" value="0" />
    <param name="kf_dist_angular" value="0" />
  </node>
<!--
  <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen">
    <remap from="imu_data" to="imu" />
    <param name="odom_used" value="false" />
    <param name="imu_used" value="true" />
    <param name="vo_used" value="false" />
    <param name="gps_used" value="false" />
  </node>
-->
  <node pkg="rviz" type="rviz" name="rviz" 
        args="-d $(find racecar)/rviz/laser_scan_matcher.rviz" />

</launch>

================================================
FILE: racecar/launch/teleop.launch
================================================
<!-- -*- mode: XML -*- -->
<launch>
  <arg name="racecar_version" default="racecar-v2" />
  <arg name="run_camera" default="false"/>


  <include file="$(find racecar)/launch/includes/$(arg racecar_version)-teleop.launch.xml">
    <arg name="racecar_version" value="$(arg racecar_version)" />
    <arg name="run_camera" value="$(arg run_camera)" />
  </include>

</launch>


================================================
FILE: racecar/maps/basement_hallways_10cm.yaml
================================================
image: basement_hallways_10cm.png
resolution: 0.100000
origin: [-30.000000, -30.000000, 0.000000]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.196



================================================
FILE: racecar/maps/basement_hallways_5cm.yml
================================================
image: basement_hallways_5cm.png
resolution: 0.050000
origin: [-30.000000, -30.000000, 0.000000]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.196



================================================
FILE: racecar/maps/short-course-33.yml
================================================
image: short-course-33.png
resolution: 0.025000
origin: [-11.50000, -5.000000, -0.090000]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.196



================================================
FILE: racecar/package.xml
================================================
<?xml version="1.0"?>
<package>
  <name>racecar</name>
  <version>0.0.1</version>
  <description>RACECAR launch scripts</description>

  <author>Michael Boulet</author>
  <maintainer email="boulet@ll.mit.edu">Michael Boulet</maintainer>
  <license>BSD</license>

  <!-- <url type="website">http://wiki.ros.org/pwm_sysfs_driver</url> -->

  <!-- <author email="jane.doe@example.com">Jane Doe</author> -->

  <buildtool_depend>catkin</buildtool_depend>

  <!--<build_depend></build_depend>-->

  <run_depend>razor_imu_9dof</run_depend>
  <run_depend>tf</run_depend>
  <run_depend>tf2_ros</run_depend>
  <run_depend>urg_node</run_depend>
  <run_depend>joy</run_depend>
  <run_depend>rosbag</run_depend>
  <run_depend>rostopic</run_depend>
  <run_depend>rviz</run_depend>

  <!-- specific to racecar-v1 -->
  <!-- <run_depend>pointgrey_camera_driver</run_depend> -->
  <!-- <run_depend>px4flow</run_depend> -->
  <!-- <run_depend>pwm_sysfs_driver</run_depend> -->

  <!-- specific to racecar-v2 -->

  <!-- mapping -->
  <run_depend>gmapping</run_depend>
  <run_depend>hector_mapping</run_depend>
  <run_depend>robot_pose_ekf</run_depend>

  <export>
  </export>
</package>


================================================
FILE: racecar/rviz/known_map_localization.rviz
================================================
Panels:
  - Class: rviz/Displays
    Help Height: 78
    Name: Displays
    Property Tree Widget:
      Expanded:
        - /Global Options1
        - /TF1/Tree1/map1
        - /TF1/Tree1/map1/odom1
        - /TF1/Tree1/map1/odom1/base_footprint1
        - /TF1/Tree1/map1/odom1/base_footprint1/base_link1
      Splitter Ratio: 0.5
    Tree Height: 531
  - Class: rviz/Selection
    Name: Selection
  - Class: rviz/Tool Properties
    Expanded:
      - /2D Pose Estimate1
      - /2D Nav Goal1
    Name: Tool Properties
    Splitter Ratio: 0.588679
  - Class: rviz/Views
    Expanded:
      - /Current View1
    Name: Views
    Splitter Ratio: 0.5
  - Class: rviz/Time
    Experimental: false
    Name: Time
    SyncMode: 0
    SyncSource: LaserScan
Visualization Manager:
  Class: ""
  Displays:
    - Alpha: 0.5
      Cell Size: 1
      Class: rviz/Grid
      Color: 160; 160; 164
      Enabled: true
      Line Style:
        Line Width: 0.03
        Value: Lines
      Name: Grid
      Normal Cell Count: 0
      Offset:
        X: 0
        Y: 0
        Z: 0
      Plane: XY
      Plane Cell Count: 10
      Reference Frame: map
      Value: true
    - Class: rviz/TF
      Enabled: false
      Frame Timeout: 15
      Frames:
        All Enabled: false
        base_footprint:
          Value: true
        base_link:
          Value: false
        camera_depth_frame:
          Value: false
        camera_depth_optical_frame:
          Value: false
        camera_link:
          Value: false
        camera_rgb_frame:
          Value: false
        camera_rgb_optical_frame:
          Value: false
        caster_back_link:
          Value: false
        caster_front_link:
          Value: false
        cliff_sensor_front_link:
          Value: false
        cliff_sensor_left_link:
          Value: false
        cliff_sensor_right_link:
          Value: false
        gyro_link:
          Value: false
        map:
          Value: true
        odom:
          Value: true
        plate_bottom_link:
          Value: false
        plate_middle_link:
          Value: false
        plate_top_link:
          Value: false
        pole_bottom_0_link:
          Value: false
        pole_bottom_1_link:
          Value: false
        pole_bottom_2_link:
          Value: false
        pole_bottom_3_link:
          Value: false
        pole_bottom_4_link:
          Value: false
        pole_bottom_5_link:
          Value: false
        pole_kinect_0_link:
          Value: false
        pole_kinect_1_link:
          Value: false
        pole_middle_0_link:
          Value: false
        pole_middle_1_link:
          Value: false
        pole_middle_2_link:
          Value: false
        pole_middle_3_link:
          Value: false
        pole_top_0_link:
          Value: false
        pole_top_1_link:
          Value: false
        pole_top_2_link:
          Value: false
        pole_top_3_link:
          Value: false
        wheel_left_link:
          Value: false
        wheel_right_link:
          Value: false
      Marker Scale: 1
      Name: TF
      Show Arrows: true
      Show Axes: true
      Show Names: true
      Tree:
        map:
          odom:
            base_footprint:
              base_link:
                camera_rgb_frame:
                  camera_depth_frame:
                    camera_depth_optical_frame:
                      {}
                  camera_link:
                    {}
                  camera_rgb_optical_frame:
                    {}
                caster_back_link:
                  {}
                caster_front_link:
                  {}
                cliff_sensor_front_link:
                  {}
                cliff_sensor_left_link:
                  {}
                cliff_sensor_right_link:
                  {}
                gyro_link:
                  {}
                plate_bottom_link:
                  {}
                plate_middle_link:
                  {}
                plate_top_link:
                  {}
                pole_bottom_0_link:
                  {}
                pole_bottom_1_link:
                  {}
                pole_bottom_2_link:
                  {}
                pole_bottom_3_link:
                  {}
                pole_bottom_4_link:
                  {}
                pole_bottom_5_link:
                  {}
                pole_kinect_0_link:
                  {}
                pole_kinect_1_link:
                  {}
                pole_middle_0_link:
                  {}
                pole_middle_1_link:
                  {}
                pole_middle_2_link:
                  {}
                pole_middle_3_link:
                  {}
                pole_top_0_link:
                  {}
                pole_top_1_link:
                  {}
                pole_top_2_link:
                  {}
                pole_top_3_link:
                  {}
                wheel_left_link:
                  {}
                wheel_right_link:
                  {}
      Update Interval: 0
      Value: false
    - Alpha: 1
      Autocompute Intensity Bounds: true
      Autocompute Value Bounds:
        Max Value: 10
        Min Value: -10
        Value: true
      Axis: Z
      Channel Name: intensity
      Class: rviz/LaserScan
      Color: 255; 0; 0
      Color Transformer: FlatColor
      Decay Time: 0
      Enabled: true
      Invert Rainbow: false
      Max Color: 255; 255; 255
      Max Intensity: 4096
      Min Color: 0; 0; 0
      Min Intensity: 0
      Name: LaserScan
      Position Transformer: XYZ
      Queue Size: 10
      Selectable: true
      Size (Pixels): 3
      Size (m): 0.03
      Style: Points
      Topic: /scan
      Use Fixed Frame: true
      Use rainbow: true
      Value: true
    - Alpha: 0.7
      Class: rviz/Map
      Color Scheme: map
      Draw Behind: false
      Enabled: true
      Name: Map
      Topic: /map
      Value: true
    - Arrow Length: 0.2
      Class: rviz/PoseArray
      Color: 0; 192; 0
      Enabled: true
      Name: Amcl Particles
      Topic: /particlecloud
      Value: true
    - Angle Tolerance: 0.1
      Class: rviz/Odometry
      Color: 0; 255; 255
      Enabled: true
      Keep: 500
      Length: 0.1
      Name: Odometry
      Position Tolerance: 0.1
      Topic: /vesc/odom
      Value: true
  Enabled: true
  Global Options:
    Background Color: 48; 48; 48
    Fixed Frame: map
    Frame Rate: 30
  Name: root
  Tools:
    - Class: rviz/MoveCamera
    - Class: rviz/Interact
      Hide Inactive Objects: true
    - Class: rviz/Select
    - Class: rviz/SetInitialPose
      Topic: /initialpose
    - Class: rviz/SetGoal
      Topic: /move_base_simple/goal
    - Class: rviz/Measure
  Value: true
  Views:
    Current:
      Angle: -1.935
      Class: rviz/TopDownOrtho
      Enable Stereo Rendering:
        Stereo Eye Separation: 0.06
        Stereo Focal Distance: 1
        Swap Stereo Eyes: false
        Value: false
      Name: Current View
      Near Clip Distance: 0.01
      Scale: 100.79
      Target Frame: base_footprint
      Value: TopDownOrtho (rviz)
      X: 1.71641
      Y: 0.715559
    Saved: ~
Window Geometry:
  Displays:
    collapsed: false
  Height: 744
  Hide Left Dock: false
  Hide Right Dock: false
  QMainWindow State: 000000ff00000000fd000000040000000000000142000002a2fc0200000005fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000002a2000000dd00ffffff000000010000010f000002a2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000028000002a2000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a0000002f600fffffffb0000000800540069006d00650100000000000004500000000000000000000002b8000002a200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
  Selection:
    collapsed: false
  Time:
    collapsed: false
  Tool Properties:
    collapsed: false
  Views:
    collapsed: false
  Width: 1301
  X: 57
  Y: -4


================================================
FILE: racecar/rviz/laser_scan_matcher.rviz
================================================
Panels:
  - Class: rviz/Displays
    Help Height: 78
    Name: Displays
    Property Tree Widget:
      Expanded:
        - /Global Options1
        - /Status1
        - /Grid1
        - /LaserScan1
        - /TF1
        - /TF1/Frames1
      Splitter Ratio: 0.5
    Tree Height: 434
  - Class: rviz/Selection
    Name: Selection
  - Class: rviz/Tool Properties
    Expanded:
      - /2D Pose Estimate1
      - /2D Nav Goal1
      - /Publish Point1
    Name: Tool Properties
    Splitter Ratio: 0.588679
  - Class: rviz/Views
    Expanded:
      - /Current View1
    Name: Views
    Splitter Ratio: 0.5
  - Class: rviz/Time
    Experimental: false
    Name: Time
    SyncMode: 0
    SyncSource: LaserScan
Visualization Manager:
  Class: ""
  Displays:
    - Alpha: 0.5
      Cell Size: 1
      Class: rviz/Grid
      Color: 160; 160; 164
      Enabled: true
      Line Style:
        Line Width: 0.03
        Value: Lines
      Name: Grid
      Normal Cell Count: 0
      Offset:
        X: 0
        Y: 0
        Z: 0
      Plane: XY
      Plane Cell Count: 10
      Reference Frame: <Fixed Frame>
      Value: true
    - Alpha: 0.2
      Autocompute Intensity Bounds: true
      Autocompute Value Bounds:
        Max Value: 10
        Min Value: -10
        Value: true
      Axis: Z
      Channel Name: intensity
      Class: rviz/LaserScan
      Color: 255; 0; 0
      Color Transformer: FlatColor
      Decay Time: 0
      Enabled: true
      Invert Rainbow: false
      Max Color: 255; 0; 0
      Max Intensity: 4096
      Min Color: 0; 0; 0
      Min Intensity: 0
      Name: LaserScan
      Position Transformer: XYZ
      Queue Size: 10
      Selectable: true
      Size (Pixels): 3
      Size (m): 0.025
      Style: Flat Squares
      Topic: /scan
      Use Fixed Frame: true
      Use rainbow: true
      Value: true
    - Class: rviz/TF
      Enabled: true
      Frame Timeout: 15
      Frames:
        All Enabled: true
        base_link:
          Value: true
        laser:
          Value: true
        world:
          Value: true
      Marker Scale: 1
      Name: TF
      Show Arrows: true
      Show Axes: true
      Show Names: true
      Tree:
        world:
          base_link:
            laser:
              {}
      Update Interval: 0
      Value: true
  Enabled: true
  Global Options:
    Background Color: 0; 0; 0
    Fixed Frame: world
    Frame Rate: 30
  Name: root
  Tools:
    - Class: rviz/Interact
      Hide Inactive Objects: true
    - Class: rviz/MoveCamera
    - Class: rviz/Select
    - Class: rviz/FocusCamera
    - Class: rviz/Measure
    - Class: rviz/SetInitialPose
      Topic: /initialpose
    - Class: rviz/SetGoal
      Topic: /move_base_simple/goal
    - Class: rviz/PublishPoint
      Single click: true
      Topic: /clicked_point
  Value: true
  Views:
    Current:
      Angle: 0
      Class: rviz/TopDownOrtho
      Enable Stereo Rendering:
        Stereo Eye Separation: 0.06
        Stereo Focal Distance: 1
        Swap Stereo Eyes: false
        Value: false
      Name: Current View
      Near Clip Distance: 0.01
      Scale: 150
      Target Frame: <Fixed Frame>
      Value: TopDownOrtho (rviz)
      X: 0
      Y: 0
    Saved: ~
Window Geometry:
  Displays:
    collapsed: false
  Height: 721
  Hide Left Dock: false
  Hide Right Dock: false
  QMainWindow State: 000000ff00000000fd00000004000000000000013c0000023dfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005300fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000360000023d000000b700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000023dfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007301000000360000023d0000009b00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004000000003efc0100000002fb0000000800540069006d00650100000000000004000000024500fffffffb0000000800540069006d00650100000000000004500000000000000000000001a90000023d00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
  Selection:
    collapsed: false
  Time:
    collapsed: false
  Tool Properties:
    collapsed: false
  Views:
    collapsed: false
  Width: 1024
  X: -2
  Y: -2


================================================
FILE: racecar/rviz/mapping.rviz
================================================
Panels:
  - Class: rviz/Displays
    Help Height: 78
    Name: Displays
    Property Tree Widget:
      Expanded:
        - /Global Options1
        - /Status1
        - /Map1
        - /LaserScan1
      Splitter Ratio: 0.5
    Tree Height: 565
  - Class: rviz/Selection
    Name: Selection
  - Class: rviz/Tool Properties
    Expanded:
      - /2D Pose Estimate1
      - /2D Nav Goal1
      - /Publish Point1
    Name: Tool Properties
    Splitter Ratio: 0.588679
  - Class: rviz/Views
    Expanded:
      - /Current View1
    Name: Views
    Splitter Ratio: 0.5
  - Class: rviz/Time
    Experimental: false
    Name: Time
    SyncMode: 0
    SyncSource: LaserScan
Visualization Manager:
  Class: ""
  Displays:
    - Alpha: 0.5
      Cell Size: 1
      Class: rviz/Grid
      Color: 160; 160; 164
      Enabled: true
      Line Style:
        Line Width: 0.03
        Value: Lines
      Name: Grid
      Normal Cell Count: 0
      Offset:
        X: 0
        Y: 0
        Z: 0
      Plane: XY
      Plane Cell Count: 10
      Reference Frame: <Fixed Frame>
      Value: true
    - Alpha: 0.7
      Class: rviz/Map
      Color Scheme: map
      Draw Behind: false
      Enabled: true
      Name: Map
      Topic: /map
      Value: true
    - Class: rviz/TF
      Enabled: true
      Frame Timeout: 15
      Frames:
        All Enabled: true
        base_footprint:
          Value: true
        base_imu_link:
          Value: true
        base_link:
          Value: true
        camera:
          Value: true
        gmapping_map:
          Value: true
        hector_map:
          Value: true
        hector_odom:
          Value: true
        hector_scanmatcher_frame:
          Value: true
        laser:
          Value: true
        px4flow:
          Value: true
      Marker Scale: 1
      Name: TF
      Show Arrows: true
      Show Axes: true
      Show Names: true
      Tree:
        gmapping_map:
          hector_map:
            hector_odom:
              base_link:
                base_footprint:
                  {}
                base_imu_link:
                  {}
                camera:
                  {}
                laser:
                  {}
                px4flow:
                  {}
            hector_scanmatcher_frame:
              {}
      Update Interval: 0
      Value: true
    - Alpha: 1
      Autocompute Intensity Bounds: true
      Autocompute Value Bounds:
        Max Value: 10
        Min Value: -10
        Value: true
      Axis: Z
      Channel Name: intensity
      Class: rviz/LaserScan
      Color: 255; 255; 255
      Color Transformer: Intensity
      Decay Time: 0
      Enabled: true
      Invert Rainbow: false
      Max Color: 255; 255; 255
      Max Intensity: 1030
      Min Color: 0; 0; 0
      Min Intensity: 370
      Name: LaserScan
      Position Transformer: XYZ
      Queue Size: 10
      Selectable: true
      Size (Pixels): 3
      Size (m): 0.08
      Style: Flat Squares
      Topic: /scan
      Use Fixed Frame: true
      Use rainbow: true
      Value: true
  Enabled: true
  Global Options:
    Background Color: 48; 48; 48
    Fixed Frame: gmapping_map
    Frame Rate: 30
  Name: root
  Tools:
    - Class: rviz/Interact
      Hide Inactive Objects: true
    - Class: rviz/MoveCamera
    - Class: rviz/Select
    - Class: rviz/FocusCamera
    - Class: rviz/Measure
    - Class: rviz/SetInitialPose
      Topic: /initialpose
    - Class: rviz/SetGoal
      Topic: /move_base_simple/goal
    - Class: rviz/PublishPoint
      Single click: true
      Topic: /clicked_point
  Value: true
  Views:
    Current:
      Angle: 0
      Class: rviz/TopDownOrtho
      Enable Stereo Rendering:
        Stereo Eye Separation: 0.06
        Stereo Focal Distance: 1
        Swap Stereo Eyes: false
        Value: false
      Name: Current View
      Near Clip Distance: 0.01
      Scale: 8.5022
      Target Frame: <Fixed Frame>
      Value: TopDownOrtho (rviz)
      X: -0.8955
      Y: -15.9022
    Saved: ~
Window Geometry:
  Displays:
    collapsed: false
  Height: 846
  Hide Left Dock: false
  Hide Right Dock: false
  QMainWindow State: 000000ff00000000fd00000004000000000000013c000002c4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000002c4000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002c4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730100000028000002c4000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002f600fffffffb0000000800540069006d0065010000000000000450000000000000000000000259000002c400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
  Selection:
    collapsed: false
  Time:
    collapsed: false
  Tool Properties:
    collapsed: false
  Views:
    collapsed: false
  Width: 1200
  X: 372
  Y: 50


================================================
FILE: racecar/scripts/joy_teleop.py
================================================
#!/usr/bin/env python
import importlib

import rospy
import genpy.message
from rospy import ROSException
import sensor_msgs.msg
import actionlib
import rostopic
import rosservice
from threading import Thread
from rosservice import ROSServiceException

import numpy as np

class JoyTeleopException(Exception):
    pass

'''
Originally from https://github.com/ros-teleop/teleop_tools
Pulled on April 28, 2017.

Edited by Winter Guerra on April 28, 2017 to allow for default actions.
'''


class JoyTeleop:
    """
    Generic joystick teleoperation node.
    Will not start without configuration, has to be stored in 'teleop' parameter.
    See config/joy_teleop.yaml for an example.
    """
    def __init__(self):
        if not rospy.has_param("teleop"):
            rospy.logfatal("no configuration was found, taking node down")
            raise JoyTeleopException("no config")

        self.publishers = {}
        self.al_clients = {}
        self.srv_clients = {}
        self.service_types = {}
        self.message_types = {}
        self.command_list = {}
        self.offline_actions = []
        self.offline_services = []

        self.old_buttons = []

        teleop_cfg = rospy.get_param("teleop")

        for i in teleop_cfg:
            if i in self.command_list:
                rospy.logerr("command {} was duplicated".format(i))
                continue
            action_type = teleop_cfg[i]['type']
            self.add_command(i, teleop_cfg[i])
            if action_type == 'topic':
                self.register_topic(i, teleop_cfg[i])
            elif action_type == 'action':
                self.register_action(i, teleop_cfg[i])
            elif action_type == 'service':
                self.register_service(i, teleop_cfg[i])
            else:
                rospy.logerr("unknown type '%s' for command '%s'", action_type, i)

        # Don't subscribe until everything has been initialized.
        rospy.Subscriber('joy', sensor_msgs.msg.Joy, self.joy_callback)

        # Run a low-freq action updater
        rospy.Timer(rospy.Duration(2.0), self.update_actions)

    def joy_callback(self, data):
        try:
            for c in self.command_list:
                if self.match_command(c, data.buttons):
                    self.run_command(c, data)
                    # Only run 1 command at a time
                    break
        except JoyTeleopException as e:
            rospy.logerr("error while parsing joystick input: %s", str(e))
        self.old_buttons = data.buttons

    def register_topic(self, name, command):
        """Add a topic publisher for a joystick command"""
        topic_name = command['topic_name']
        try:
            topic_type = self.get_message_type(command['message_type'])
            self.publishers[topic_name] = rospy.Publisher(topic_name, topic_type, queue_size=1)
        except JoyTeleopException as e:
            rospy.logerr("could not register topic for command {}: {}".format(name, str(e)))

    def register_action(self, name, command):
        """Add an action client for a joystick command"""
        action_name = command['action_name']
        try:
            action_type = self.get_message_type(self.get_action_type(action_name))
            self.al_clients[action_name] = actionlib.SimpleActionClient(action_name, action_type)
            if action_name in self.offline_actions:
                self.offline_actions.remove(action_name)
        except JoyTeleopException:
            if action_name not in self.offline_actions:
                self.offline_actions.append(action_name)

    class AsyncServiceProxy(object):
        def __init__(self, name, service_class, persistent=True):
            try:
                rospy.wait_for_service(name, timeout=2.0)
            except ROSException:
                raise JoyTeleopException("Service {} is not available".format(name))
            self._service_proxy = rospy.ServiceProxy(name, service_class, persistent)
            self._thread = Thread(target=self._service_proxy, args=[])

        def __del__(self):
            # try to join our thread - no way I know of to interrupt a service
            # request
            if self._thread.is_alive():
                self._thread.join(1.0)

        def __call__(self, request):
            if self._thread.is_alive():
                self._thread.join(0.01)
                if self._thread.is_alive():
                    return False

            self._thread = Thread(target=self._service_proxy, args=[request])
            self._thread.start()
            return True

    def register_service(self, name, command):
        """ Add an AsyncServiceProxy for a joystick command """
        service_name = command['service_name']
        try:
            service_type = self.get_service_type(service_name)
            self.srv_clients[service_name] = self.AsyncServiceProxy(
                service_name,
                service_type)

            if service_name in self.offline_services:
                self.offline_services.remove(service_name)
        except JoyTeleopException:
            if service_name not in self.offline_services:
                self.offline_services.append(service_name)

    def match_command(self, c, buttons):
        """Find a command matching a joystick configuration"""
        # Buttons is a vector of the shape [0,1,0,1....
        # Turn it into a vector of form [1, 3...
        button_indexes = np.argwhere(buttons).flatten()

        # Check if the pressed buttons match the commands exactly.
        buttons_match = np.array_equal(self.command_list[c]['buttons'], button_indexes)

        #print button_indexes
        if buttons_match:
            return True

        # This might also be a default command.
        # We need to check if ANY commands match this set of pressed buttons.
        any_commands_matched = np.any([ np.array_equal(command['buttons'], button_indexes) for name, command in self.command_list.iteritems()])

        # Return the final result.
        return (buttons_match) or (not any_commands_matched and self.command_list[c]['is_default'])

    def add_command(self, name, command):
        """Add a command to the command list"""
        # Check if this is a default command
        if 'is_default' not in command:
            command['is_default'] = False
        
        if command['type'] == 'topic':
            if 'deadman_buttons' not in command:
                command['deadman_buttons'] = []
            command['buttons'] = command['deadman_buttons']
        elif command['type'] == 'action':
            if 'action_goal' not in command:
                command['action_goal'] = {}
        elif command['type'] == 'service':
            if 'service_request' not in command:
                command['service_request'] = {}
        self.command_list[name] = command

    def run_command(self, command, joy_state):
        """Run a joystick command"""
        cmd = self.command_list[command]
        if cmd['type'] == 'topic':
            self.run_topic(command, joy_state)
        elif cmd['type'] == 'action':
            if cmd['action_name'] in self.offline_actions:
                rospy.logerr("command {} was not played because the action "
                             "server was unavailable. Trying to reconnect..."
                             .format(cmd['action_name']))
                self.register_action(command, self.command_list[command])
            else:
                if joy_state.buttons != self.old_buttons:
                    self.run_action(command, joy_state)
        elif cmd['type'] == 'service':
            if cmd['service_name'] in self.offline_services:
                rospy.logerr("command {} was not played because the service "
                             "server was unavailable. Trying to reconnect..."
                             .format(cmd['service_name']))
                self.register_service(command, self.command_list[command])
            else:
                if joy_state.buttons != self.old_buttons:
                    self.run_service(command, joy_state)
        else:
            raise JoyTeleopException('command {} is neither a topic publisher nor an action or service client'
                                     .format(command))

    def run_topic(self, c, joy_state):
        cmd = self.command_list[c]
        msg = self.get_message_type(cmd['message_type'])()

        if 'message_value' in cmd:
            for param in cmd['message_value']:
                self.set_member(msg, param['target'], param['value'])

        else:
            for mapping in cmd['axis_mappings']:
                if len(joy_state.axes)<=mapping['axis']:
                  rospy.logerr('Joystick has only {} axes (indexed from 0), but #{} was referenced in config.'.format(len(joy_state.axes), mapping['axis']))
                  val = 0.0
                else:
                  val = joy_state.axes[mapping['axis']] * mapping.get('scale', 1.0) + mapping.get('offset', 0.0)

                self.set_member(msg, mapping['target'], val)
                
        self.publishers[cmd['topic_name']].publish(msg)

    def run_action(self, c, joy_state):
        cmd = self.command_list[c]
        goal = self.get_message_type(self.get_action_type(cmd['action_name'])[:-6] + 'Goal')()
        genpy.message.fill_message_args(goal, [cmd['action_goal']])
        self.al_clients[cmd['action_name']].send_goal(goal)

    def run_service(self, c, joy_state):
        cmd = self.command_list[c]
        request = self.get_service_type(cmd['service_name'])._request_class()
        # should work for requests, too
        genpy.message.fill_message_args(request, [cmd['service_request']])
        if not self.srv_clients[cmd['service_name']](request):
            rospy.loginfo('Not sending new service request for command {} because previous request has not finished'
                          .format(c))

    def set_member(self, msg, member, value):
        ml = member.split('.')
        if len(ml) < 1:
            return
        target = msg
        for i in ml[:-1]:
            target = getattr(target, i)
        setattr(target, ml[-1], value)

    def get_message_type(self, type_name):
        if type_name not in self.message_types:
            try:
                package, message = type_name.split('/')
                mod = importlib.import_module(package + '.msg')
                self.message_types[type_name] = getattr(mod, message)
            except ValueError:
                raise JoyTeleopException("message type format error")
            except ImportError:
                raise JoyTeleopException("module {} could not be loaded".format(package))
            except AttributeError:
                raise JoyTeleopException("message {} could not be loaded from module {}".format(package, message))
        return self.message_types[type_name]

    def get_action_type(self, action_name):
        try:
            return rostopic._get_topic_type(rospy.resolve_name(action_name) + '/goal')[0][:-4]
        except TypeError:
            raise JoyTeleopException("could not find action {}".format(action_name))

    def get_service_type(self, service_name):
        if service_name not in self.service_types:
            try:
                self.service_types[service_name] = rosservice.get_service_class_by_name(service_name)
            except ROSServiceException, e:
                raise JoyTeleopException("service {} could not be loaded: {}".format(service_name, str(e)))
        return self.service_types[service_name]

    def update_actions(self, evt=None):
        for name, cmd in self.command_list.iteritems():
            if cmd['type'] != 'action':
                continue
            if cmd['action_name'] in self.offline_actions:
                self.register_action(name, cmd)


if __name__ == "__main__":
    try:
        rospy.init_node('joy_teleop')
        jt = JoyTeleop()
        rospy.spin()
    except JoyTeleopException:
        pass
    except rospy.ROSInterruptException:
        pass


================================================
FILE: racecar-vm.rosinstall
================================================
- setup-file: {local-name: /opt/ros/kinetic/setup.sh}
- git: {local-name: src/racecar,         version: master,        uri: 'https://github.com/mit-racecar/racecar.git'}
- git: {local-name: src/vesc,            version: master,        uri: 'https://github.com/mit-racecar/vesc.git'}
- git: {local-name: src/racecar-simulator,            version: master,        uri: 'https://github.com/mit-racecar/racecar-simulator.git'}


================================================
FILE: racecar.rosinstall
================================================
- setup-file: {local-name: /opt/ros/kinetic/setup.sh}
- git: {local-name: src/racecar,         version: master,        uri: 'https://github.com/mit-racecar/racecar.git'}
- git: {local-name: src/vesc,            version: master,        uri: 'https://github.com/mit-racecar/vesc.git'}
- git: {local-name: src/zed_wrapper,     version: 6c06bb0a3c32aa2dec4a539e296f6ee1d6937518,        uri: 'https://github.com/stereolabs/zed-ros-wrapper.git'}
Download .txt
gitextract_ho3gnwhp/

├── .gitignore
├── ackermann_cmd_mux/
│   ├── .cproject
│   ├── .gitignore
│   ├── .project
│   ├── .pydevproject
│   ├── .settings/
│   │   └── language.settings.xml
│   ├── CHANGELOG.rst
│   ├── CMakeLists.txt
│   ├── LICENSE
│   ├── cfg/
│   │   └── reload.cfg
│   ├── include/
│   │   └── ackermann_cmd_mux/
│   │       ├── ackermann_cmd_mux_nodelet.hpp
│   │       ├── ackermann_cmd_subscribers.hpp
│   │       └── exceptions.hpp
│   ├── launch/
│   │   ├── ackermann_cmd_mux.launch
│   │   ├── reconfigure.launch
│   │   └── standalone.launch
│   ├── package.xml
│   ├── param/
│   │   ├── example.yaml
│   │   └── reconfigure.yaml
│   ├── plugins/
│   │   └── nodelets.xml
│   └── src/
│       ├── ackermann_cmd_mux_nodelet.cpp
│       ├── ackermann_cmd_subscribers.cpp
│       └── throttle_interpolator.py
├── racecar/
│   ├── CMakeLists.txt
│   ├── LICENSE
│   ├── config/
│   │   └── racecar-v2/
│   │       ├── high_level_mux.yaml
│   │       ├── joy_teleop.yaml
│   │       ├── low_level_mux.yaml
│   │       ├── sensors.yaml
│   │       └── vesc.yaml
│   ├── launch/
│   │   ├── includes/
│   │   │   ├── common/
│   │   │   │   ├── joy_teleop.launch.xml
│   │   │   │   └── sensors.launch.xml
│   │   │   ├── racecar-v2/
│   │   │   │   ├── static_transforms.launch.xml
│   │   │   │   ├── velodyne.launch.xml
│   │   │   │   └── vesc.launch.xml
│   │   │   └── racecar-v2-teleop.launch.xml
│   │   ├── known_map_localization.launch
│   │   ├── mux.launch
│   │   ├── replay_bag_file/
│   │   │   ├── replay_bag_file.launch
│   │   │   ├── replay_bag_mapping.launch
│   │   │   └── replay_bag_with_lidar_processing.launch
│   │   └── teleop.launch
│   ├── maps/
│   │   ├── basement_hallways_10cm.yaml
│   │   ├── basement_hallways_5cm.yml
│   │   └── short-course-33.yml
│   ├── package.xml
│   ├── rviz/
│   │   ├── known_map_localization.rviz
│   │   ├── laser_scan_matcher.rviz
│   │   └── mapping.rviz
│   └── scripts/
│       └── joy_teleop.py
├── racecar-vm.rosinstall
└── racecar.rosinstall
Download .txt
SYMBOL INDEX (52 symbols across 7 files)

FILE: ackermann_cmd_mux/include/ackermann_cmd_mux/ackermann_cmd_mux_nodelet.hpp
  type ackermann_cmd_mux (line 31) | namespace ackermann_cmd_mux {
    class AckermannCmdMuxNodelet (line 37) | class AckermannCmdMuxNodelet : public nodelet::Nodelet
      method AckermannCmdMuxNodelet (line 42) | AckermannCmdMuxNodelet()
      class AckermannCmdFunctor (line 72) | class AckermannCmdFunctor
        method AckermannCmdFunctor (line 79) | AckermannCmdFunctor(unsigned int idx, AckermannCmdMuxNodelet* node) :
      class TimerFunctor (line 91) | class TimerFunctor
        method TimerFunctor (line 98) | TimerFunctor(unsigned int idx, AckermannCmdMuxNodelet* node) :

FILE: ackermann_cmd_mux/include/ackermann_cmd_mux/ackermann_cmd_subscribers.hpp
  type ackermann_cmd_mux (line 45) | namespace ackermann_cmd_mux {
    class AckermannCmdSubscribers (line 54) | class AckermannCmdSubscribers
      class AckermannCmdSubs (line 61) | class AckermannCmdSubs
        method AckermannCmdSubs (line 74) | AckermannCmdSubs(unsigned int idx) : idx(idx), active(false) {}
      method AckermannCmdSubscribers (line 79) | AckermannCmdSubscribers() : allowed(VACANT) { }
      method size (line 82) | std::vector<AckermannCmdSubs>::size_type size() { return list.size(); }
      method AckermannCmdSubs (line 83) | AckermannCmdSubs& operator [] (unsigned int idx) { return list[idx]; }
        method AckermannCmdSubs (line 74) | AckermannCmdSubs(unsigned int idx) : idx(idx), active(false) {}

FILE: ackermann_cmd_mux/include/ackermann_cmd_mux/exceptions.hpp
  type ackermann_cmd_mux (line 26) | namespace ackermann_cmd_mux {
    class FileNotFoundException (line 32) | class FileNotFoundException: public std::runtime_error {
      method FileNotFoundException (line 34) | FileNotFoundException(const std::string& msg)
    class EmptyCfgException (line 39) | class EmptyCfgException: public std::runtime_error {
      method EmptyCfgException (line 41) | EmptyCfgException()
    class YamlException (line 46) | class YamlException: public std::runtime_error {
      method YamlException (line 48) | YamlException(const std::string& msg)

FILE: ackermann_cmd_mux/src/ackermann_cmd_mux_nodelet.cpp
  type ackermann_cmd_mux (line 24) | namespace ackermann_cmd_mux {

FILE: ackermann_cmd_mux/src/ackermann_cmd_subscribers.cpp
  type ackermann_cmd_mux (line 22) | namespace ackermann_cmd_mux {

FILE: ackermann_cmd_mux/src/throttle_interpolator.py
  class InterpolateThrottle (line 10) | class InterpolateThrottle:
    method __init__ (line 11) | def __init__(self):
    method _run (line 56) | def _run(self):
    method _publish_throttle_command (line 59) | def _publish_throttle_command(self, evt):
    method _process_throttle_command (line 67) | def _process_throttle_command(self,msg):
    method _publish_servo_command (line 73) | def _publish_servo_command(self, evt):
    method _process_servo_command (line 80) | def _process_servo_command(self,msg):

FILE: racecar/scripts/joy_teleop.py
  class JoyTeleopException (line 16) | class JoyTeleopException(Exception):
  class JoyTeleop (line 27) | class JoyTeleop:
    method __init__ (line 33) | def __init__(self):
    method joy_callback (line 72) | def joy_callback(self, data):
    method register_topic (line 83) | def register_topic(self, name, command):
    method register_action (line 92) | def register_action(self, name, command):
    class AsyncServiceProxy (line 104) | class AsyncServiceProxy(object):
      method __init__ (line 105) | def __init__(self, name, service_class, persistent=True):
      method __del__ (line 113) | def __del__(self):
      method __call__ (line 119) | def __call__(self, request):
    method register_service (line 129) | def register_service(self, name, command):
    method match_command (line 144) | def match_command(self, c, buttons):
    method add_command (line 164) | def add_command(self, name, command):
    method run_command (line 182) | def run_command(self, command, joy_state):
    method run_topic (line 209) | def run_topic(self, c, joy_state):
    method run_action (line 229) | def run_action(self, c, joy_state):
    method run_service (line 235) | def run_service(self, c, joy_state):
    method set_member (line 244) | def set_member(self, msg, member, value):
    method get_message_type (line 253) | def get_message_type(self, type_name):
    method get_action_type (line 267) | def get_action_type(self, action_name):
    method get_service_type (line 273) | def get_service_type(self, service_name):
    method update_actions (line 281) | def update_actions(self, evt=None):
Condensed preview — 52 files, each showing path, character count, and a content snippet. Download the .json file or copy for the full structured content (113K chars).
[
  {
    "path": ".gitignore",
    "chars": 36,
    "preview": "# -*- mode: gitignore; -*-\n*~\n\\#*\\#\n"
  },
  {
    "path": "ackermann_cmd_mux/.cproject",
    "chars": 5725,
    "preview": "<?xml version=\"1.0\" encoding=\"UTF-8\" standalone=\"no\"?>\n<?fileVersion 4.0.0?><cproject storage_type_id=\"org.eclipse.cdt.c"
  },
  {
    "path": "ackermann_cmd_mux/.gitignore",
    "chars": 17,
    "preview": "/bin\n/build\n/lib\n"
  },
  {
    "path": "ackermann_cmd_mux/.project",
    "chars": 2505,
    "preview": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<projectDescription>\n\t<name>ackermann_cmd_mux</name>\n\t<comment></comment>\n\t<proje"
  },
  {
    "path": "ackermann_cmd_mux/.pydevproject",
    "chars": 304,
    "preview": "<?xml version=\"1.0\" encoding=\"UTF-8\" standalone=\"no\"?>\n<?eclipse-pydev version=\"1.0\"?>\n\n<pydev_project>\n<pydev_property "
  },
  {
    "path": "ackermann_cmd_mux/.settings/language.settings.xml",
    "chars": 989,
    "preview": "<?xml version=\"1.0\" encoding=\"UTF-8\" standalone=\"no\"?>\n<project>\n\t<configuration id=\"cdt.managedbuild.toolchain.gnu.base"
  },
  {
    "path": "ackermann_cmd_mux/CHANGELOG.rst",
    "chars": 1954,
    "preview": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package ackermann_cmd_mux\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0"
  },
  {
    "path": "ackermann_cmd_mux/CMakeLists.txt",
    "chars": 1519,
    "preview": "cmake_minimum_required(VERSION 2.8.3)\nproject(ackermann_cmd_mux)\nfind_package(catkin REQUIRED COMPONENTS \n\troscpp \n\tplug"
  },
  {
    "path": "ackermann_cmd_mux/LICENSE",
    "chars": 1647,
    "preview": "# Software License Agreement (BSD License)\n#\n# Copyright (c) 2012 Yujin Robot, Daniel Stonier, Jorge Santos\n# All rights"
  },
  {
    "path": "ackermann_cmd_mux/cfg/reload.cfg",
    "chars": 407,
    "preview": "#!/usr/bin/env python2\n\nPACKAGE = \"ackermann_cmd_mux\"\n\nfrom dynamic_reconfigure.parameter_generator_catkin import *\n\ngen"
  },
  {
    "path": "ackermann_cmd_mux/include/ackermann_cmd_mux/ackermann_cmd_mux_nodelet.hpp",
    "chars": 3371,
    "preview": "/**\n * @file /include/ackermann_cmd_mux/ackermann_cmd_mux_nodelet.hpp\n *\n * @brief Structure for the ackermann_cmd_mux.\n"
  },
  {
    "path": "ackermann_cmd_mux/include/ackermann_cmd_mux/ackermann_cmd_subscribers.hpp",
    "chars": 3497,
    "preview": "/**\n * @file /include/ackermann_cmd_mux/ackermann_cmd_subscribers.hpp\n *\n * @brief Structure for the ackermann_cmd_mux.\n"
  },
  {
    "path": "ackermann_cmd_mux/include/ackermann_cmd_mux/exceptions.hpp",
    "chars": 1713,
    "preview": "/**\n * @file /ackermann_cmd_mux/include/ackermann_cmd_mux/exceptions.hpp\n *\n * @brief Exception classes for ackermann_cm"
  },
  {
    "path": "ackermann_cmd_mux/launch/ackermann_cmd_mux.launch",
    "chars": 453,
    "preview": "<!--\n  Ackermann Command Multiplexer launcher\n  -->\n\n<launch>\n  <arg name=\"nodelet_manager_name\"  default=\"nodelet_manag"
  },
  {
    "path": "ackermann_cmd_mux/launch/reconfigure.launch",
    "chars": 368,
    "preview": "<!--\n  Test the dynamic reconfiguration of the ackermann_cmd_mux. Run this after running the example launcher.\n -->\n<lau"
  },
  {
    "path": "ackermann_cmd_mux/launch/standalone.launch",
    "chars": 867,
    "preview": "<!--\n  Example standalone launcher for the ackermann command multiplexer.\n  \n  For best results you would usually load t"
  },
  {
    "path": "ackermann_cmd_mux/package.xml",
    "chars": 1747,
    "preview": "<package>\n  <name>ackermann_cmd_mux</name>\n  <version>0.7.0</version>\n  <description>\n     A multiplexer for ackermann c"
  },
  {
    "path": "ackermann_cmd_mux/param/example.yaml",
    "chars": 1509,
    "preview": "# Created on: Oct 29, 2012\n#     Author: jorge\n# Configuration for subscribers to ackermann_cmd sources. This file is pr"
  },
  {
    "path": "ackermann_cmd_mux/param/reconfigure.yaml",
    "chars": 780,
    "preview": "# Another example configuration file, though this one is used to test the dynamic reconfiguration\n# of the ackermann_cmd"
  },
  {
    "path": "ackermann_cmd_mux/plugins/nodelets.xml",
    "chars": 343,
    "preview": "<library path=\"lib/libackermann_cmd_mux_nodelet\">\n  <class name=\"ackermann_cmd_mux/AckermannCmdMuxNodelet\"\n         type"
  },
  {
    "path": "ackermann_cmd_mux/src/ackermann_cmd_mux_nodelet.cpp",
    "chars": 6162,
    "preview": "/**\n * @file /src/ackermann_cmd_mux_nodelet.cpp\n *\n * @brief  Implementation for the ackermann command multiplexer\n *\n *"
  },
  {
    "path": "ackermann_cmd_mux/src/ackermann_cmd_subscribers.cpp",
    "chars": 1885,
    "preview": "/**\n * @file /src/ackermann_cmd_subscribers.cpp\n *\n * @brief  Subscriber handlers for the ackermann_cmd_mux\n *\n * Licens"
  },
  {
    "path": "ackermann_cmd_mux/src/throttle_interpolator.py",
    "chars": 4090,
    "preview": "#!/usr/bin/env python\nimport rospy\n\nfrom std_msgs.msg import Float64\n\n# import some utils.\nimport numpy as np\nimport cop"
  },
  {
    "path": "racecar/CMakeLists.txt",
    "chars": 5506,
    "preview": "cmake_minimum_required(VERSION 2.8.3)\nproject(racecar)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like f"
  },
  {
    "path": "racecar/LICENSE",
    "chars": 1679,
    "preview": "# Software License Agreement (BSD License)\n#\n# Copyright (c) 2016 Massachusetts Institute of Technology.\n# All rights re"
  },
  {
    "path": "racecar/config/racecar-v2/high_level_mux.yaml",
    "chars": 1168,
    "preview": "# Individual subscriber configuration:\n#   name:           Source name\n#   topic:          The topic that provides acker"
  },
  {
    "path": "racecar/config/racecar-v2/joy_teleop.yaml",
    "chars": 1381,
    "preview": "joy_node:\n  deadzone: 0.01\n  autorepeat_rate: 20\n  coalesce_interval: 0.01\n\nteleop:\n  # Default mode - Stop for safety\n "
  },
  {
    "path": "racecar/config/racecar-v2/low_level_mux.yaml",
    "chars": 901,
    "preview": "# Individual subscriber configuration:\n#   name:           Source name\n#   topic:          The topic that provides acker"
  },
  {
    "path": "racecar/config/racecar-v2/sensors.yaml",
    "chars": 90,
    "preview": "\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",
    "chars": 1163,
    "preview": "\n# erpm (electrical rpm) = speed_to_erpm_gain * speed (meters / second) + speed_to_erpm_offset\n# for offset=0. speed_to_"
  },
  {
    "path": "racecar/launch/includes/common/joy_teleop.launch.xml",
    "chars": 376,
    "preview": "<!-- -*- mode: XML -*- -->\n<launch>\n  <arg name=\"racecar_version\" />\n  <arg name=\"joy_teleop_config\"\n       default=\"$(f"
  },
  {
    "path": "racecar/launch/includes/common/sensors.launch.xml",
    "chars": 1062,
    "preview": "<!-- -*- mode: XML -*- -->\n<launch>\n  <arg name=\"racecar_version\" />\n  <arg name=\"sensors_config\"\n       default=\"$(find"
  },
  {
    "path": "racecar/launch/includes/racecar-v2/static_transforms.launch.xml",
    "chars": 623,
    "preview": "<!-- -*- mode: XML -*- -->\n<launch>\n\n  <node pkg=\"tf2_ros\" type=\"static_transform_publisher\" name=\"base_link_to_imu\" \n  "
  },
  {
    "path": "racecar/launch/includes/racecar-v2/velodyne.launch.xml",
    "chars": 2084,
    "preview": "<!-- -*- mode: XML -*- -->\n<!-- run velodyne_pointcloud/CloudNodelet in a nodelet manager for a VLP-16 -->\n\n<launch>\n\n  "
  },
  {
    "path": "racecar/launch/includes/racecar-v2/vesc.launch.xml",
    "chars": 1072,
    "preview": "<!-- -*- mode: XML -*- -->\n<launch>\n  <arg name=\"racecar_version\" />\n\n  <arg name=\"vesc_config\" default=\"$(find racecar)"
  },
  {
    "path": "racecar/launch/includes/racecar-v2-teleop.launch.xml",
    "chars": 1037,
    "preview": "<!-- -*- mode: XML -*- -->\n<launch>\n  <arg name=\"racecar_version\" default=\"racecar-v2\" />\n  <arg name=\"run_camera\" defau"
  },
  {
    "path": "racecar/launch/known_map_localization.launch",
    "chars": 2823,
    "preview": "<launch>\n\n  <!-- known map server -->\n  <arg name=\"map\"            default=\"$(find racecar)/maps/short-course-33.yml\" />"
  },
  {
    "path": "racecar/launch/mux.launch",
    "chars": 2066,
    "preview": "<!-- -*- mode: XML -*- -->\n<!--\n This work is sponsored by the Department of the Air Force under Air Force\n Contract FA8"
  },
  {
    "path": "racecar/launch/replay_bag_file/replay_bag_file.launch",
    "chars": 393,
    "preview": "<!-- -*- mode: XML -*- -->\n<launch>\n  <!-- launch script arguments -->\n  <arg name=\"bag\"/>\n  <arg name=\"rate\" default=\"1"
  },
  {
    "path": "racecar/launch/replay_bag_file/replay_bag_mapping.launch",
    "chars": 3770,
    "preview": "<!-- -*- mode: XML -*- -->\n<launch>\n  <!-- launch script arguments -->\n  <arg name=\"bag\"/>\n  <arg name=\"rate\" default=\"1"
  },
  {
    "path": "racecar/launch/replay_bag_file/replay_bag_with_lidar_processing.launch",
    "chars": 1239,
    "preview": "<!-- -*- mode: XML -*- -->\n<launch>\n  <!-- launch script arguments -->\n  <arg name=\"bag\"/>\n  <arg name=\"rate\" default=\"1"
  },
  {
    "path": "racecar/launch/teleop.launch",
    "chars": 373,
    "preview": "<!-- -*- mode: XML -*- -->\n<launch>\n  <arg name=\"racecar_version\" default=\"racecar-v2\" />\n  <arg name=\"run_camera\" defau"
  },
  {
    "path": "racecar/maps/basement_hallways_10cm.yaml",
    "chars": 150,
    "preview": "image: basement_hallways_10cm.png\nresolution: 0.100000\norigin: [-30.000000, -30.000000, 0.000000]\nnegate: 0\noccupied_thr"
  },
  {
    "path": "racecar/maps/basement_hallways_5cm.yml",
    "chars": 149,
    "preview": "image: basement_hallways_5cm.png\nresolution: 0.050000\norigin: [-30.000000, -30.000000, 0.000000]\nnegate: 0\noccupied_thre"
  },
  {
    "path": "racecar/maps/short-course-33.yml",
    "chars": 142,
    "preview": "image: short-course-33.png\nresolution: 0.025000\norigin: [-11.50000, -5.000000, -0.090000]\nnegate: 0\noccupied_thresh: 0.6"
  },
  {
    "path": "racecar/package.xml",
    "chars": 1170,
    "preview": "<?xml version=\"1.0\"?>\n<package>\n  <name>racecar</name>\n  <version>0.0.1</version>\n  <description>RACECAR launch scripts<"
  },
  {
    "path": "racecar/rviz/known_map_localization.rviz",
    "chars": 8630,
    "preview": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n      "
  },
  {
    "path": "racecar/rviz/laser_scan_matcher.rviz",
    "chars": 4940,
    "preview": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n      "
  },
  {
    "path": "racecar/rviz/mapping.rviz",
    "chars": 5728,
    "preview": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n      "
  },
  {
    "path": "racecar/scripts/joy_teleop.py",
    "chars": 12064,
    "preview": "#!/usr/bin/env python\nimport importlib\n\nimport rospy\nimport genpy.message\nfrom rospy import ROSException\nimport sensor_m"
  },
  {
    "path": "racecar-vm.rosinstall",
    "chars": 422,
    "preview": "- setup-file: {local-name: /opt/ros/kinetic/setup.sh}\n- git: {local-name: src/racecar,         version: master,        u"
  },
  {
    "path": "racecar.rosinstall",
    "chars": 440,
    "preview": "- setup-file: {local-name: /opt/ros/kinetic/setup.sh}\n- git: {local-name: src/racecar,         version: master,        u"
  }
]

About this extraction

This page contains the full source code of the mit-racecar/racecar GitHub repository, extracted and formatted as plain text for AI agents and large language models (LLMs). The extraction includes 52 files (102.1 KB), approximately 28.7k tokens, and a symbol index with 52 extracted functions, classes, methods, constants, and types. Use this with OpenClaw, Claude, ChatGPT, Cursor, Windsurf, or any other AI tool that accepts text input. You can copy the full output to your clipboard or download it as a .txt file.

Extracted by GitExtract — free GitHub repo to text converter for AI. Built by Nikandr Surkov.

Copied to clipboard!