Skip to content
Snippets Groups Projects
Commit cdf806eb authored by Fernando Herrero's avatar Fernando Herrero
Browse files

Initial commit

parents
No related branches found
No related tags found
No related merge requests found
Showing with 1537 additions and 0 deletions
cmake_minimum_required(VERSION 2.8.3)
project(iri_helena_rosnav)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
## 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 tag for "message_generation"
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a exec_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
# )
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## 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 your 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 iri_helena_rosnav
# CATKIN_DEPENDS other_catkin_pkg
# DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
# ${catkin_INCLUDE_DIRS}
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/iri_helena_rosnav.cpp
# )
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/iri_helena_rosnav_node.cpp)
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_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 ${PROJECT_NAME} ${PROJECT_NAME}_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}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_iri_helena_rosnav.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)
<?xml version="1.0"?>
<!-- -->
<launch>
<arg name="rviz" default="true"/>
<arg name="ns" default="helena"/>
<arg name="path" default="$(find iri_helena_rosnav)"/>
<arg name="map_frame_id" default="map"/>
<arg name="odom_frame_id" default="$(arg ns)/odom"/>
<arg name="base_frame_id" default="$(arg ns)/base_footprint"/>
<arg name="map_topic" default="/$(arg ns)/map"/>
<arg name="map_service" default="/$(arg ns)/static_map"/>
<arg name="odom_topic" default="/$(arg ns)/odom"/>
<arg name="cmd_vel_topic" default="/$(arg ns)/navigation/cmd_vel"/>
<arg name="scan_topic" default="/$(arg ns)/scans"/>
<arg name="use_map" default="true"/>
<arg name="use_map_server" default="true"/>
<arg name="map_name" default="willow"/>
<arg name="use_amcl" default="true"/>
<arg name="amcl_config" default="$(arg path)/params/amcl.yaml"/>
<arg name="initial_x" default="0.0"/>
<arg name="initial_y" default="0.0"/>
<arg name="initial_yaw" default="0.0"/>
<arg name="use_fake_loc" default="false"/>
<arg name="use_gmapping" default="false"/>
<arg name="gmapping_scan_topic" default="/$(arg ns)/front_hokuyo_scan"/>
<arg name="gmapping_config" default="$(arg path)/params/gmapping.yaml"/>
<arg name="resolution" default="0.1"/>
<arg name="use_cmd_vel_mux" default="true"/>
<arg name="nodelet_manager_name" default="nodelet_manager"/>
<arg name="cmd_vel_mux_config" default="$(arg path)/params/mux.yaml"/>
<arg name="local_planner" default="dwa"/>
<arg name="global_planner" default="global_planner"/>
<arg name="output" default="screen" />
<arg name="launch_prefix" default="" />
<include file="$(find iri_rosnav)/launch/nav.launch">
<arg name="ns" value="$(arg ns)"/>
<arg name="path" value="$(arg path)"/>
<arg name="map_frame_id" value="$(arg map_frame_id)"/>
<arg name="odom_frame_id" value="$(arg odom_frame_id)"/>
<arg name="base_frame_id" value="$(arg base_frame_id)"/>
<arg name="map_topic" value="$(arg map_topic)"/>
<arg name="map_service" value="$(arg map_service)"/>
<arg name="odom_topic" value="$(arg odom_topic)"/>
<arg name="cmd_vel_topic" value="$(arg cmd_vel_topic)"/>
<arg name="scan_topic" value="$(arg scan_topic)"/>
<arg name="use_map_server" value="$(arg use_map_server)"/>
<arg name="map_name" value="$(arg map_name)"/>
<arg name="use_amcl" value="$(arg use_amcl)"/>
<arg name="amcl_config" value="$(arg amcl_config)"/>
<arg name="initial_x" value="$(arg initial_x)"/>
<arg name="initial_y" value="$(arg initial_y)"/>
<arg name="initial_yaw" value="$(arg initial_yaw)"/>
<arg name="use_fake_loc" value="$(arg use_fake_loc)"/>
<arg name="use_gmapping" value="$(arg use_gmapping)"/>
<arg name="gmapping_scan_topic" value="/$(arg gmapping_scan_topic)"/>
<arg name="gmapping_config" value="$(arg gmapping_config)"/>
<arg name="resolution" value="$(arg resolution)"/>
<arg name="use_cmd_vel_mux" value="$(arg use_cmd_vel_mux)"/>
<arg name="nodelet_manager_name" value="$(arg nodelet_manager_name)"/>
<arg name="cmd_vel_mux_config" value="$(arg cmd_vel_mux_config)"/>
<arg name="local_planner" value="$(arg local_planner)"/>
<arg name="global_planner" value="$(arg global_planner)"/>
<arg name="output" value="$(arg output)" />
<arg name="launch_prefix" value="$(arg launch_prefix)" />
</include>
<group ns="$(arg ns)">
<node name="front_laser_relay"
pkg="topic_tools"
type="relay"
args="front_hokuyo_scan $(arg scan_topic)"/>
<node name="rear_laser_relay"
pkg="topic_tools"
type="relay"
args="rear_hokuyo_scan $(arg scan_topic)"/>
</group>
<node name="rviz"
pkg="rviz"
type="rviz"
if="$(arg rviz)"
args="-d $(arg path)/rviz/$(arg ns).rviz">
</node>
</launch>
<?xml version="1.0"?>
<!-- -->
<launch>
<arg name="rviz" default="true"/>
<arg name="ns" default="helena"/>
<arg name="path" default="$(find iri_helena_rosnav)"/>
<arg name="map_frame_id" default="map"/>
<arg name="odom_frame_id" default="$(arg ns)/odom"/>
<arg name="base_frame_id" default="$(arg ns)/base_footprint"/>
<arg name="map_topic" default="/$(arg ns)/map"/>
<arg name="map_service" default="/$(arg ns)/static_map"/>
<arg name="odom_topic" default="/$(arg ns)/odom"/>
<arg name="cmd_vel_topic" default="/$(arg ns)/navigation/cmd_vel"/>
<arg name="scan_topic" default="/$(arg ns)/scans"/>
<arg name="use_map" default="true"/>
<arg name="use_map_server" default="false"/>
<arg name="map_name" default="willow"/>
<arg name="use_amcl" default="false"/>
<arg name="amcl_config" default="$(arg path)/params/helena_amcl.yaml"/>
<arg name="initial_x" default="0.0"/>
<arg name="initial_y" default="0.0"/>
<arg name="initial_yaw" default="0.0"/>
<arg name="use_fake_loc" default="false"/>
<arg name="use_gmapping" default="true"/>
<arg name="gmapping_scan_topic" default="/$(arg ns)/front_hokuyo_scan"/>
<arg name="gmapping_config" default="$(arg path)/params/helena_gmapping.yaml"/>
<arg name="resolution" default="0.2"/>
<arg name="use_cmd_vel_mux" default="true"/>
<arg name="nodelet_manager_name" default="nodelet_manager"/>
<arg name="cmd_vel_mux_config" default="$(arg path)/params/helena_mux.yaml"/>
<arg name="local_planner" default="dwa"/>
<arg name="global_planner" default="rrt_planner"/>
<arg name="output" default="screen" />
<arg name="launch_prefix" default="" />
<include file="$(find iri_rosnav)/launch/nav.launch">
<arg name="ns" value="$(arg ns)"/>
<arg name="path" value="$(arg path)"/>
<arg name="map_frame_id" value="$(arg map_frame_id)"/>
<arg name="odom_frame_id" value="$(arg odom_frame_id)"/>
<arg name="base_frame_id" value="$(arg base_frame_id)"/>
<arg name="map_topic" value="$(arg map_topic)"/>
<arg name="map_service" value="$(arg map_service)"/>
<arg name="odom_topic" value="$(arg odom_topic)"/>
<arg name="cmd_vel_topic" value="$(arg cmd_vel_topic)"/>
<arg name="scan_topic" value="$(arg scan_topic)"/>
<arg name="use_map_server" value="$(arg use_map_server)"/>
<arg name="map_name" value="$(arg map_name)"/>
<arg name="use_amcl" value="$(arg use_amcl)"/>
<arg name="amcl_config" value="$(arg amcl_config)"/>
<arg name="initial_x" value="$(arg initial_x)"/>
<arg name="initial_y" value="$(arg initial_y)"/>
<arg name="initial_yaw" value="$(arg initial_yaw)"/>
<arg name="use_fake_loc" value="$(arg use_fake_loc)"/>
<arg name="use_gmapping" value="$(arg use_gmapping)"/>
<arg name="gmapping_scan_topic" value="/$(arg gmapping_scan_topic)"/>
<arg name="gmapping_config" value="$(arg gmapping_config)"/>
<arg name="resolution" value="$(arg resolution)"/>
<arg name="use_cmd_vel_mux" value="$(arg use_cmd_vel_mux)"/>
<arg name="nodelet_manager_name" value="$(arg nodelet_manager_name)"/>
<arg name="cmd_vel_mux_config" value="$(arg cmd_vel_mux_config)"/>
<arg name="local_planner" value="$(arg local_planner)"/>
<arg name="global_planner" value="$(arg global_planner)"/>
<arg name="output" value="$(arg output)" />
<arg name="launch_prefix" value="$(arg launch_prefix)" />
</include>
<group ns="$(arg ns)">
<node name="front_laser_relay"
pkg="topic_tools"
type="relay"
args="front_hokuyo_scan $(arg scan_topic)"/>
<node name="rear_laser_relay"
pkg="topic_tools"
type="relay"
args="rear_hokuyo_scan $(arg scan_topic)"/>
</group>
<node name="rviz"
pkg="rviz"
type="rviz"
if="$(arg rviz)"
args="-d $(find iri_helena_rosnav)/rviz/$(arg ns).rviz">
</node>
</launch>
<?xml version="1.0"?>
<package format="2">
<name>iri_helena_rosnav</name>
<version>0.0.0</version>
<description>The iri_helena_rosnav package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="fherrero@todo.todo">fherrero</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/iri_helena_rosnav</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>
map_frame_id: map
odom_frame_id: helena/odom
base_frame_id: helena/base_footprint
initial_x: 0.0
initial_y: 0.0
initial_a: 0.0
# filer parameters
min_particles: 100
max_particles: 5000
kld_err: 0.01
kld_z: 0.99
update_min_d: 0.2
update_min_a: 0.5236
resample_interval: 2
transform_tolerance: 0.1
recovery_alpha_slow: 0.0
recovery_alpha_fast: 0.0
initial_cov_xx: 0.25
initial_cov_yy: 0.25
initial_cov_aa: 0.0685
gui_publish_rate: -1.0
save_pose_rate: 0.5
use_map_topic: false
first_map_only: false
# laser parameters
laser_min_range: -1.0
laser_max_range: -1.0
laser_max_beams: 30
laser_z_hit: 0.95
laser_z_short: 0.1
laser_z_max: 0.05
laser_z_rand: 0.05
laser_sigma_hit: 0.2
laser_lambda_short: 0.1
laser_likelihood_max_dist: 2.0
laser_model_type: 'likelihood_field'
# odom parameters
odom_model_type: "diff"
odom_alpha1: 0.2
odom_alpha2: 0.2
odom_alpha3: 0.2
odom_alpha4: 0.2
odom_alpha5: 0.2
tf_broadcast: true
# footprint parameters
#footprint: [[0.35, 0.35], [0.35, -0.35], [-0.35,-0.35 ], [-0.35, 0.35]]
robot_radius: 0.5
footprint_padding: -0.1
footprint_topic: /helena/move_base/local_costmap/footprint
published_footprint_topic: false
robot_base_frame: /helena/base_footprint
track_unknown_space: false
always_send_full_costmap: false
transform_tolerance: 1.0
width: 10.0
height: 10.0
resolution: 0.1
origin_x: 0.0
origin_y: 0.0
obstacle_layer:
enabled: true
track_unknown_space: true
transform_tolerance: 0.2
max_obstacle_height: 1.0
footprint_clearing_enabled: false
combination_method: 1
observation_sources: front_laser rear_laser
front_laser: {
sensor_frame: /helena/front_hokuyo_scan_frame,
data_type: LaserScan,
topic: /helena/front_hokuyo_scan,
observation_persistence: 0.0,
marking: true,
clearing: true,
min_obstacle_height: 0.05,
max_obstacle_height: 1.8,
expected_update_rate: 10,
obstacle_range: 30.0,
raytrace_range: 40.0
}
rear_laser: {
sensor_frame: /helena/rear_hokuyo_scan_frame,
data_type: LaserScan,
topic: /helena/rear_hokuyo_scan,
observation_persistence: 0.0,
marking: true,
clearing: true,
min_obstacle_height: 0.05,
max_obstacle_height: 1.8,
expected_update_rate: 10,
obstacle_range: 30.0,
raytrace_range: 40.0
}
inflation_layer:
enabled: true
inflate_unknown: false
inflation_radius: 2.0
cost_scaling_factor: 5.0
inflation_radius: 0.5
#local_costmap: ###namespace added when loading parameters in move_base.launch
global_frame: /helena/odom
update_frequency: 5.0
publish_frequency: 2.0
rolling_window: true
width: 10.0
height: 10.0
resolution: 0.1
origin_x: 0.0
origin_y: 0.0
#costmap plugins
plugins:
- {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"}
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
#obstacle_layer:
#enabled: true
#track_unknown_space: true
#transform_tolerance: 0.2
#max_obstacle_height: 1.0
#footprint_clearing_enabled: false
#combination_method: 1
#observation_sources: front_laser rear_laser
#front_laser: {
#sensor_frame: /helena/front_hokuyo_scan_frame,
#data_type: LaserScan,
#topic: /helena/front_hokuyo_scan,
#observation_persistence: 0.0,
#marking: true,
#clearing: true,
#min_obstacle_height: 0.05,
#max_obstacle_height: 1.8,
#expected_update_rate: 10,
#obstacle_range: 30.0,
#raytrace_range: 40.0
#}
#rear_laser: {
#sensor_frame: /helena/rear_hokuyo_scan_frame,
#data_type: LaserScan,
#topic: /helena/rear_hokuyo_scan,
#observation_persistence: 0.0,
#marking: true,
#clearing: true,
#min_obstacle_height: 0.05,
#max_obstacle_height: 1.8,
#expected_update_rate: 10,
#obstacle_range: 30.0,
#raytrace_range: 40.0
#}
#inflation_layer:
#enabled: true
#inflate_unknown: false
#inflation_radius: 2.0
#cost_scaling_factor: 5.0
#inflation_radius: 0.5
#global_costmap: ###namespace added when loading parameters in move_base.launch
global_frame: /map
update_frequency: 1.0
publish_frequency: 0.0
rolling_window: false
plugins:
- {name: static_layer, type: "costmap_2d::StaticLayer"}
- {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"}
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
static_layer:
enabled: true
map_topic: /map
first_map_only: false
subscribe_to_updates: false
unknown_cost_value: -1
use_maximum: false
lethal_cost_threshold: 100
track_unknown_space: true
trinary_costmap: true
#obstacle_layer:
#enabled: true
#track_unknown_space: true
#transform_tolerance: 0.2
#max_obstacle_height: 1.0
#footprint_clearing_enabled: false
#combination_method: 1
#observation_sources: front_laser rear_laser
#front_laser: {
#sensor_frame: /helena/front_hokuyo_scan_frame,
#data_type: LaserScan,
#topic: /helena/front_hokuyo_scan,
#observation_persistence: 0.0,
#marking: true,
#clearing: true,
#min_obstacle_height: 0.05,
#max_obstacle_height: 1.8,
#expected_update_rate: 10,
#obstacle_range: 30.0,
#raytrace_range: 40.0
#}
#rear_laser: {
#sensor_frame: /helena/rear_hokuyo_scan_frame,
#data_type: LaserScan,
#topic: /helena/rear_hokuyo_scan,
#observation_persistence: 0.0,
#marking: true,
#clearing: true,
#min_obstacle_height: 0.05,
#max_obstacle_height: 1.8,
#expected_update_rate: 10,
#obstacle_range: 30.0,
#raytrace_range: 40.0
#}
#inflation_layer:
#enabled: true
#inflate_unknown: false
#inflation_radius: 2.0
#cost_scaling_factor: 5.0
#inflation_radius: 0.5
\ No newline at end of file
#global_costmap: ###namespace added when loading parameters in move_base.launch
global_frame: /helena/odom
update_frequency: 1.0
publish_frequency: 0.0
rolling_window: true
transform_tolerance: 1.0
width: 20.0
height: 20.0
resolution: 0.2
origin_x: 0.0
origin_y: 0.0
plugins:
- {name: obstacle_layer, type: "costmap_2d::VoxelLayer"}
- {name: inflation_layer, type: "costmap_2d::InflationLayer"}
#obstacle_layer:
#enabled: true
#track_unknown_space: true
#transform_tolerance: 0.2
#max_obstacle_height: 1.0
#footprint_clearing_enabled: false
#combination_method: 1
#observation_sources: front_laser rear_laser
#front_laser: {
#sensor_frame: /helena/front_hokuyo_scan_frame,
#data_type: LaserScan,
#topic: /helena/front_hokuyo_scan,
#observation_persistence: 0.0,
#marking: true,
#clearing: true,
#min_obstacle_height: 0.05,
#max_obstacle_height: 1.8,
#expected_update_rate: 10,
#obstacle_range: 30.0,
#raytrace_range: 40.0
#}
#rear_laser: {
#sensor_frame: /helena/rear_hokuyo_scan_frame,
#data_type: LaserScan,
#topic: /helena/rear_hokuyo_scan,
#observation_persistence: 0.0,
#marking: true,
#clearing: true,
#min_obstacle_height: 0.05,
#max_obstacle_height: 1.8,
#expected_update_rate: 10,
#obstacle_range: 30.0,
#raytrace_range: 40.0
#}
#inflation_layer:
#enabled: true
#inflate_unknown: false
#inflation_radius: 2.0
#cost_scaling_factor: 5.0
#inflation_radius: 0.5
base_global_planner: "global_planner/GlobalPlanner"
GlobalPlanner: #default
allow_unknown: false
default_tolerance: 0.0
publish_potential: false
publish_scale: 100
old_navfn_behavior: false
planner_costmap_publish_frequency: 0.0
#planner to use
use_dijkstra: true
use_quadratic: true
use_grid_path: false
# planner parameters
lethal_cost: 253
neutral_cost: 50
cost_factor: 3.0
planner_window_x: 0.0
planner_window_y: 0.0
# orientation fileter
orientation_mode: 0
orientation_window_size: 1
base_global_planner: "rrt_planner/RrtPlanner"
RrtPlanner:
debug: true
star: true
dimension: 2
range: 17.0
precision: 0.1
neighbour_threshold: 1
max_nodes: 2000
max_time: 0.5
#reconfigurable
robot_radius: 0.5
frequency: 1
frame_id: map
frame_map: map
cost_function_type: 1 #0:Euclidean, 1: SFM
simulator_type: 1 #0:Static, 1: ConstSpeed, 2: LinearSFM
edge_connector_type: 0 #0:Linear
\ No newline at end of file
map_update_interval: 5.0
maxUrange: 29.0
sigma: 0.05
kernelSize: 1
lstep: 0.05
astep: 0.05
iterations: 5
lsigma: 0.075
ogain: 3.0
lskip: 0
srr: 0.1
srt: 0.2
str: 0.1
stt: 0.2
linearUpdate: 0.5
angularUpdate: 0.5
temporalUpdate: 10.0
resampleThreshold: 0.5
particles: 80
xmin: -5.0
ymin: -5.0
xmax: 5.0
ymax: 5.0
delta: 0.1
llsamplerange: 0.01
llsamplestep: 0.01
lasamplerange: 0.005
lasamplestep: 0.005
\ No newline at end of file
base_local_planner: "dwa_local_planner/DWAPlannerROS"
latch_xy_goal_tolerance: true
DWAPlannerROS:
# robot configuration parameters
max_trans_vel: 0.5
min_trans_vel: 0.1
max_vel_x: 0.5
min_vel_x: -0.5
max_vel_y: 0.0
min_vel_y: 0.0
max_rot_vel: 2.0
min_rot_vel: 0.2
acc_lim_theta: 3.0
acc_lim_x: 1.0
acc_lim_y: 0.0
acc_limit_trans: 1.0
rot_stopped_vel: 0.1
trans_stopped_vel: 0.1
# goal tolerance parameters
xy_goal_tolerance: 0.1
yaw_goal_tolerance: 0.1
# Forward simulation parameters
sim_time: 2.5
sim_granularity: 0.1
angular_sim_granularity: 0.1
vx_samples: 21
vy_samples: 1
vth_samples: 20
controller_frequency: 20.0 # defines the sim_period
# Trajectory scoring parameters
path_distance_bias: 32.0
goal_distance_bias: 32.0
occdist_scale: 0.01
twirling_scale: 0.0
stop_time_buffer: 0.2
forward_point_distance: 0.325
scaling_speed: 0.25
max_scaling_factor: 0.2
# Oscillation prevention parameters
oscillation_reset_dist: 0.05
oscillation_reset_angle: 0.2
# global plan parameters
prune_plan: true
#not in dynamic reconfigure
publish_traj_pc: false
#global_frame_id: /robot/base_footprint
publish_cost_grid_pc: false
#base_global_planner: #defined in the global planner parameter file
#base_local_planner: #define in the local planner parameter file
recovery_behavior_enabled: false
recovery_behaviors:
- {name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}
- {name: rotate_recovery, type: rotate_recovery/RotateRecovery}
- {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}
controller_frequency: 10.0
planner_patience: 5.0
controller_patience: 5.0
planner_frequency: 0.0
max_planning_retries: -1
conservative_reset_dist: 3.0
clearing_rotation_allowed: false
clearing_radius: 0.46
shutdown_costmaps: false
oscillation_timeout: 0.0
oscillation_distance: 0.5
subscribers:
- name: "Default input"
topic: "/helena/default/cmd_vel"
timeout: 0.1
priority: 0
short_desc: "The default cmd_vel, controllers unaware that we are multiplexing cmd_vel should come here"
- name: "Platform orientation"
topic: "/helena/orientation/cmd_vel"
timeout: 0.1
priority: 4
short_desc: "Platform orientation to people"
- name: "Navigation stack"
topic: "/helena/navigation/cmd_vel"
timeout: 0.5
priority: 5
short_desc: "Navigation stack controller"
- name: "Teleop"
topic: "/helena/teleop/cmd_vel"
timeout: 0.1
priority: 10
short_desc: "Teleop wii/ps3 pad"
#publisher: "/helena/mux/cmd_vel"
publisher: "/helena/cmd_vel"
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Status1
- /Sensors1
- /Sensors1/Odometry1/Shape1
- /Nav1
Splitter Ratio: 0.5
Tree Height: 633
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.588679016
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: FrontLaserScan
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.0299999993
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
- Class: rviz/TF
Enabled: true
Frame Timeout: 15
Frames:
All Enabled: true
helena/base_footprint:
Value: true
helena/base_link:
Value: true
helena/front_hokuyo_base:
Value: true
helena/front_hokuyo_scan_frame:
Value: true
helena/front_left_axle:
Value: true
helena/front_left_hub:
Value: true
helena/front_left_wheel:
Value: true
helena/front_right_axle:
Value: true
helena/front_right_hub:
Value: true
helena/front_right_wheel:
Value: true
helena/front_sonar:
Value: true
helena/odom:
Value: true
helena/rear_hokuyo_base:
Value: true
helena/rear_hokuyo_scan_frame:
Value: true
helena/rear_left_axle:
Value: true
helena/rear_left_hub:
Value: true
helena/rear_left_wheel:
Value: true
helena/rear_right_axle:
Value: true
helena/rear_right_hub:
Value: true
helena/rear_right_wheel:
Value: true
helena/rear_sonar:
Value: true
helena/sensors_base:
Value: true
helena/top_plate:
Value: true
map:
Value: true
Marker Scale: 0.5
Name: TF
Show Arrows: false
Show Axes: true
Show Names: true
Tree:
map:
helena/odom:
helena/base_footprint:
helena/base_link:
helena/front_left_axle:
helena/front_left_hub:
helena/front_left_wheel:
{}
helena/front_right_axle:
helena/front_right_hub:
helena/front_right_wheel:
{}
helena/front_sonar:
{}
helena/rear_left_axle:
helena/rear_left_hub:
helena/rear_left_wheel:
{}
helena/rear_right_axle:
helena/rear_right_hub:
helena/rear_right_wheel:
{}
helena/rear_sonar:
{}
helena/sensors_base:
helena/front_hokuyo_base:
helena/front_hokuyo_scan_frame:
{}
helena/rear_hokuyo_base:
helena/rear_hokuyo_scan_frame:
{}
helena/top_plate:
{}
Update Interval: 0
Value: true
- Alpha: 1
Class: rviz/RobotModel
Collision Enabled: false
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_footprint:
Alpha: 1
Show Axes: false
Show Trail: false
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
front_hokuyo_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
front_hokuyo_scan_frame:
Alpha: 1
Show Axes: false
Show Trail: false
front_left_axle:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
front_left_hub:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
front_left_wheel:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
front_right_axle:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
front_right_hub:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
front_right_wheel:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
front_sonar:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rear_hokuyo_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rear_hokuyo_scan_frame:
Alpha: 1
Show Axes: false
Show Trail: false
rear_left_axle:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rear_left_hub:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rear_left_wheel:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rear_right_axle:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rear_right_hub:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rear_right_wheel:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
rear_sonar:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
sensors_base:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
top_plate:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Name: RobotModel
Robot Description: helena/robot_description
TF Prefix: helena
Update Interval: 0
Value: true
Visual Enabled: true
- Class: rviz/Group
Displays:
- Angle Tolerance: 0.300000012
Class: rviz/Odometry
Covariance:
Orientation:
Alpha: 0.5
Color: 255; 255; 127
Color Style: Unique
Frame: Local
Offset: 1
Scale: 1
Value: true
Position:
Alpha: 0.300000012
Color: 204; 51; 204
Scale: 1
Value: true
Value: false
Enabled: true
Keep: 100
Name: Odometry
Position Tolerance: 0.300000012
Shape:
Alpha: 0.5
Axes Length: 1
Axes Radius: 0.100000001
Color: 255; 25; 0
Head Length: 0.0500000007
Head Radius: 0.0500000007
Shaft Length: 0.25
Shaft Radius: 0.0250000004
Value: Arrow
Topic: /helena/odom
Unreliable: false
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; 85; 0
Color Transformer: FlatColor
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 999999
Min Color: 0; 0; 0
Min Intensity: 999999
Name: FrontLaserScan
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.00999999978
Style: Points
Topic: /helena/front_hokuyo_scan
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
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; 170; 127
Color Transformer: FlatColor
Decay Time: 0
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 999999
Min Color: 0; 0; 0
Min Intensity: 999999
Name: RearLaserScan
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 3
Size (m): 0.00999999978
Style: Points
Topic: /helena/rear_hokuyo_scan
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
Enabled: true
Name: Sensors
- Class: rviz/Group
Displays:
- Alpha: 0.699999988
Class: rviz/Map
Color Scheme: map
Draw Behind: true
Enabled: true
Name: Map
Topic: /helena/map
Unreliable: false
Use Timestamp: false
Value: true
- Alpha: 1
Class: rviz/Polygon
Color: 25; 255; 0
Enabled: true
Name: FootprintPolygon
Topic: /helena/move_base/local_costmap/footprint
Unreliable: false
Value: true
- Alpha: 0.5
Class: rviz/Map
Color Scheme: costmap
Draw Behind: true
Enabled: false
Name: LocalCostmapMap
Topic: /helena/move_base/local_costmap/costmap
Unreliable: false
Use Timestamp: false
Value: false
- Alpha: 0.699999988
Class: rviz/Map
Color Scheme: costmap
Draw Behind: true
Enabled: false
Name: GlobalCostmapMap
Topic: /helena/move_base/global_costmap/costmap
Unreliable: false
Use Timestamp: false
Value: false
- Alpha: 1
Axes Length: 1
Axes Radius: 0.100000001
Class: rviz/Pose
Color: 255; 255; 0
Enabled: true
Head Length: 0.300000012
Head Radius: 0.100000001
Name: GoalPose
Shaft Length: 1
Shaft Radius: 0.0500000007
Shape: Arrow
Topic: /helena/move_base_simple/goal
Unreliable: false
Value: true
- Class: rviz/Group
Displays:
- Alpha: 1
Buffer Length: 1
Class: rviz/Path
Color: 255; 0; 0
Enabled: true
Head Diameter: 0.300000012
Head Length: 0.200000003
Length: 0.300000012
Line Style: Lines
Line Width: 0.0299999993
Name: LocalPath
Offset:
X: 0
Y: 0
Z: 0
Pose Color: 255; 85; 255
Pose Style: None
Radius: 0.0299999993
Shaft Diameter: 0.100000001
Shaft Length: 0.100000001
Topic: /helena/move_base/DWAPlannerROS/local_plan
Unreliable: false
Value: true
- Alpha: 1
Buffer Length: 1
Class: rviz/Path
Color: 25; 255; 0
Enabled: true
Head Diameter: 0.300000012
Head Length: 0.200000003
Length: 0.300000012
Line Style: Lines
Line Width: 0.0299999993
Name: GlobalPath
Offset:
X: 0
Y: 0
Z: 0
Pose Color: 255; 85; 255
Pose Style: None
Radius: 0.0299999993
Shaft Diameter: 0.100000001
Shaft Length: 0.100000001
Topic: /helena/move_base/DWAPlannerROS/global_plan
Unreliable: false
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: total_cost
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: false
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 622.77002
Min Color: 0; 0; 0
Min Intensity: 0
Name: CostPointCloud2
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 10
Size (m): 0.100000001
Style: Points
Topic: /helena/move_base/DWAPlannerROS/cost_cloud
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: false
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Max Value: 10
Min Value: -10
Value: true
Axis: Z
Channel Name: total_cost
Class: rviz/PointCloud2
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: false
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 67.1999969
Min Color: 0; 0; 0
Min Intensity: 62.4000015
Name: TrajectoryPointCloud2
Position Transformer: XYZ
Queue Size: 10
Selectable: true
Size (Pixels): 10
Size (m): 0.00999999978
Style: Squares
Topic: /helena/move_base/DWAPlannerROS/trajectory_cloud
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: false
Enabled: true
Name: DWA_local_planner
- Class: rviz/Group
Displays:
- Alpha: 1
Buffer Length: 1
Class: rviz/Path
Color: 25; 255; 0
Enabled: true
Head Diameter: 0.300000012
Head Length: 0.200000003
Length: 0.300000012
Line Style: Lines
Line Width: 0.0299999993
Name: GlobalPath
Offset:
X: 0
Y: 0
Z: 0
Pose Color: 255; 85; 255
Pose Style: None
Radius: 0.0299999993
Shaft Diameter: 0.100000001
Shaft Length: 0.100000001
Topic: /helena/move_base/GlobalPlanner/plan
Unreliable: false
Value: true
- Alpha: 0.699999988
Class: rviz/Map
Color Scheme: costmap
Draw Behind: true
Enabled: false
Name: PotentialMap
Topic: /helena/move_base/GlobalPlanner/potential
Unreliable: false
Use Timestamp: false
Value: false
Enabled: true
Name: GlobalPlanner
Enabled: true
Name: Nav
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: 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: /helena/initialpose
- Class: rviz/SetGoal
Topic: /helena/move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
- Attractors: ~
Class: rviz_sfm_plugins/SetAttractor2D
- Class: rviz_sfm_plugins/SetRepulsor2D
Repulsors: ~
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 17.6234169
Enable Stereo Rendering:
Stereo Eye Separation: 0.0599999987
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: false
Focal Shape Size: 0.0500000007
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.00999999978
Pitch: 0.785398185
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 0.785398185
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 846
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd00000004000000000000016a00000308fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000308000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000308fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000308000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650000000000000004b00000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000003400000030800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1200
X: 75
Y: 34
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment