diff --git a/rois_2dnav_gazebo/CMakeLists.txt b/rois_2dnav_gazebo/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..022de1ef82fe9a9569b6513bc566a2e1f2c725d6
--- /dev/null
+++ b/rois_2dnav_gazebo/CMakeLists.txt
@@ -0,0 +1,207 @@
+cmake_minimum_required(VERSION 2.8.3)
+project(rois_2dnav_gazebo)
+
+## 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 COMPONENTS
+ amcl
+ map_server
+ move_base
+ rois_gazebo
+)
+
+## 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 rois_2dnav_gazebo
+# CATKIN_DEPENDS amcl map_server move_base rois_gazebo
+# 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}/rois_2dnav_gazebo.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/rois_2dnav_gazebo_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 for installation
+## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
+# install(TARGETS ${PROJECT_NAME}_node
+# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+# )
+
+## Mark libraries for installation
+## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
+# install(TARGETS ${PROJECT_NAME}
+# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+# RUNTIME DESTINATION ${CATKIN_GLOBAL_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_rois_2dnav_gazebo.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)
diff --git a/rois_2dnav_gazebo/config/amcl_params.yaml b/rois_2dnav_gazebo/config/amcl_params.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..eb1cfbd3fdfa13c27a1f9213fc73dc84ef2806d4
--- /dev/null
+++ b/rois_2dnav_gazebo/config/amcl_params.yaml
@@ -0,0 +1,59 @@
+min_particles: 100
+max_particles: 5000
+
+kld_err: 0.01
+kld_z: 0.99
+
+update_min_d: 0.01
+update_min_a: 0.01
+
+resample_interval: 2
+
+transform_tolerance: 0.1
+
+recovery_alpha_slow: 0.001
+recovery_alpha_fast: 0.1
+
+initial_pose_x: 0.0
+initial_pose_y: 0.0
+initial_pose_a: 0.0
+initial_cov_xx: 0.25
+initial_cov_yy: 0.25
+initial_cov_aa: 0.07
+
+gui_publish_rate: 10.0
+
+save_pose_rate: 0.5
+
+use_map_topic: true
+
+first_map_only: false
+
+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_model_type: diff-corrected
+
+odom_alpha1: 0.3
+odom_alpha2: 0.3
+odom_alpha3: 0.3
+odom_alpha4: 0.3
+odom_alpha5: 0.1
+
+odom_frame_id: odom
+base_frame_id: base_link
+global_frame_id: map
+
+tf_broadcast: true
diff --git a/rois_2dnav_gazebo/config/costmap/costmap_common_params.yaml b/rois_2dnav_gazebo/config/costmap/costmap_common_params.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..63fa6eb7ed41d8e730ad21601fb7cd029ee7aa37
--- /dev/null
+++ b/rois_2dnav_gazebo/config/costmap/costmap_common_params.yaml
@@ -0,0 +1,25 @@
+obstacle_range: 5.0
+raytrace_range: 10.0
+
+footprint: [[0.25, -0.18], [0.25, 0.18], [-0.15, 0.18], [-0.15, -0.18]]
+inflation_radius: 0.3
+cost_scaling_factor: 10.0
+
+origin_z: 0.0
+z_resolution: 0.02
+z_voxels: 0.02
+publish_voxel_map: true
+
+observation_sources: lrf_sensor
+lrf_sensor: {
+ sensor_frame: lrf_link,
+ data_type: LaserScan,
+ topic: /scan,
+ # expected_update_rate: 1.0,
+ observation_persistence: 0.0,
+ marking: true,
+ clearing: true,
+ min_obstacle_height: 0.2,
+ max_obstacle_height: 1.0,
+}
+
diff --git a/rois_2dnav_gazebo/config/costmap/global_costmap_params.yaml b/rois_2dnav_gazebo/config/costmap/global_costmap_params.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..e503908e0c9485ae29b31f844f564237a3cf0eeb
--- /dev/null
+++ b/rois_2dnav_gazebo/config/costmap/global_costmap_params.yaml
@@ -0,0 +1,9 @@
+global_costmap:
+ global_frame: map
+ robot_base_frame: base_link
+ update_frequency: 3.0
+ publish_frequency: 3.0
+ static_map: true
+ rolling_window: false
+ transform_tolerance: 1.0
+
diff --git a/rois_2dnav_gazebo/config/costmap/local_costmap_params.yaml b/rois_2dnav_gazebo/config/costmap/local_costmap_params.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..fe1fd30535a911f3b1670323ab86ac20723a35ac
--- /dev/null
+++ b/rois_2dnav_gazebo/config/costmap/local_costmap_params.yaml
@@ -0,0 +1,11 @@
+local_costmap:
+ global_frame: odom
+ robot_base_frame: base_link
+ update_frequency: 8.0
+ publish_frequency: 7.0
+ width: 10.0
+ height: 10.0
+ resolution: 0.02
+ meter_scoring: true
+ static_map: false
+ rolling_window: true
diff --git a/rois_2dnav_gazebo/config/move_base_params.yaml b/rois_2dnav_gazebo/config/move_base_params.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..86ed2ca14d818d15974e56d5d89ecba8869dacc4
--- /dev/null
+++ b/rois_2dnav_gazebo/config/move_base_params.yaml
@@ -0,0 +1,15 @@
+controller_frequency: 5.0
+controller_patience: 10.0
+
+planner_patience: 5.0
+planner_frequency: 2.0
+
+recovery_behavior_enabled: true
+clearing_rotation_allowed: true
+shutdown_costmaps: false
+
+oscillation_timeout: 10.0
+oscillation_distance: 0.2
+
+max_planning_retries: 40
+conservative_reset_dist: 6.0
diff --git a/rois_2dnav_gazebo/config/planner/base_global_planner_params.yaml b/rois_2dnav_gazebo/config/planner/base_global_planner_params.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..da175a814e9a894023b201e41b3028896bff7c00
--- /dev/null
+++ b/rois_2dnav_gazebo/config/planner/base_global_planner_params.yaml
@@ -0,0 +1,9 @@
+base_global_planner: global_planner/GlobalPlanner
+GlobalPlanner:
+ allow_unknown: false
+ default_tolerance: 1.5
+ visualize_potential: false
+ use_dijkstra: true
+ use_quadratic: true
+ use_grid_path: false
+ old_navfn_behavior: false
diff --git a/rois_2dnav_gazebo/config/planner/base_local_planner_params.yaml b/rois_2dnav_gazebo/config/planner/base_local_planner_params.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..6ec9a2c59816d1961fbf90b62d8defecf8a79421
--- /dev/null
+++ b/rois_2dnav_gazebo/config/planner/base_local_planner_params.yaml
@@ -0,0 +1,31 @@
+TrajectoryPlannerROS:
+ max_vel_x: 2.0
+ min_vel_x: 1.0
+ max_vel_theta: 2.0
+ min_vel_theta: -2.0
+
+ min_in_place_rotational_vel: 1.0
+
+ acc_lim_x: 1.0
+ acc_lim_y: 0.0
+ acc_lim_theta: 3.2
+
+ holonomic_robot: false
+
+ yaw_goal_tolerance: 0.1
+ xy_goal_tolerance: 0.1
+
+ sim_time: 2.0
+ controller_frequency: 5.0
+ # Length of view when rotate
+ heading_lookahead: 15.0
+ # Use method of Dynamic Window Approach
+ heading_scoring: false
+ heading_scoring_timestamp: 0.5
+ dwa: true
+
+ # Show cost map
+ publish_cost_grid_pc: true
+ global_frame_id: map
+
+ meter_scoring: false
diff --git a/rois_2dnav_gazebo/config/planner/recovery_behaviors.yaml b/rois_2dnav_gazebo/config/planner/recovery_behaviors.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..65d063bc22be388867a7c1de2265ac134388f733
--- /dev/null
+++ b/rois_2dnav_gazebo/config/planner/recovery_behaviors.yaml
@@ -0,0 +1,61 @@
+recovery_behavior_enabled: true
+recovery_behaviors:
+ - name: 'conservative_reset'
+ type: 'clear_costmap_recovery/ClearCostmapRecovery'
+ - name: 'rotate_recovery_1'
+ type: 'rotate_recovery/RotateRecovery'
+ - name: 'aggressive_reset'
+ type: 'clear_costmap_recovery/ClearCostmapRecovery'
+ - name: 'rotate_recovery_2'
+ type: 'rotate_recovery/RotateRecovery'
+ - name: 'rotate_recovery_3'
+ type: 'rotate_recovery/RotateRecovery'
+ # - name: 'step_back_and_max_steer_recovery'
+ # type: 'step_back_and_max_steer_recovery/StepBackAndMaxSteerRecovery'
+
+conservative_reset:
+ reset_distance: 10.0
+
+rotate_recovery_1:
+ sim_granularity: 0.017
+ max_rotational_vel: -1.0
+ min_in_place_rotational_vel: -1.0
+
+aggressive_reset:
+ reset_distance: 0.0
+
+rotate_recovery_2:
+ sim_granularity: 0.017
+ max_rotational_vel: -1.0
+ min_in_place_rotational_vel: -1.0
+
+rotate_recovery_3:
+ sim_granularity: 0.017
+ max_rotational_vel: -1.0
+ min_in_place_rotational_vel: -1.0
+
+# step_back_and_max_steer_recovery:
+# # 最初の一回だけ旋回したい場合にtrue
+# only_single_steering: true
+# # リカバリ行動の試行回数[回]
+# trial_times : 3
+# # 障害物までの許容距離[m].
+# #-- 移動中に,移動方向に対して最も近い障害物がこの距離以内に出現したら停止する.
+# obstacle_patience : 0.5
+# #-- 移動中に,障害物を確認する頻度[回/sec]
+# obstacle_check_frequency: 5.0
+# # 障害物探索時の角度の分解能[rad] costmapアクセス数を低減したいときに調整する.
+# sim_angle_resolution: 0.1
+# # back(初回後退時の速度[m/s], 移動距離[m], タイムアウト[sec])
+# linear_vel_back : -1.5
+# step_back_length : 0.6
+# step_back_timeout : 15.0
+# # steer(旋回時の直進速度[m/s], 回転速さ(環境に寄って±が変わる)[rad/s], 目標回転角度[rad], タイムアウト[sec])
+# linear_vel_steer : 0.3
+# angular_speed_steer : 1.0
+# turn_angle : 0.78
+# steering_timeout : 15.0
+# # forward(旋回→直進→旋回の直進時の速度[m/s], 目標移動距離[m])
+# linear_vel_forward : 0.3
+# step_forward_length : 1.0
+# step_forward_timeout: 15.0
diff --git a/rois_2dnav_gazebo/launch/amcl.launch b/rois_2dnav_gazebo/launch/amcl.launch
new file mode 100644
index 0000000000000000000000000000000000000000..3d9fb4fa495c7c063184aff90311c2bb46944173
--- /dev/null
+++ b/rois_2dnav_gazebo/launch/amcl.launch
@@ -0,0 +1,5 @@
+
+
+
+
+
diff --git a/rois_gazebo/launch/generate_2dmap.launch b/rois_2dnav_gazebo/launch/generate_2dmap.launch
similarity index 100%
rename from rois_gazebo/launch/generate_2dmap.launch
rename to rois_2dnav_gazebo/launch/generate_2dmap.launch
diff --git a/rois_2dnav_gazebo/launch/move_base.launch b/rois_2dnav_gazebo/launch/move_base.launch
new file mode 100644
index 0000000000000000000000000000000000000000..bef6ff6486549f7fec108f41e1af2c3a4a8d5601
--- /dev/null
+++ b/rois_2dnav_gazebo/launch/move_base.launch
@@ -0,0 +1,18 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/rois_2dnav_gazebo/map/lab_corridor/lab_corridor.pgm b/rois_2dnav_gazebo/map/lab_corridor/lab_corridor.pgm
new file mode 100644
index 0000000000000000000000000000000000000000..fd8b0cc258ff8d41c80fd9dd27558d33f59c902f
--- /dev/null
+++ b/rois_2dnav_gazebo/map/lab_corridor/lab_corridor.pgm
@@ -0,0 +1,5 @@
+P5
+# CREATOR: map_saver.cpp 0.050 m/pix
+4000 4000
+255
+
\ No newline at end of file
diff --git a/rois_2dnav_gazebo/map/lab_corridor/lab_corridor.yaml b/rois_2dnav_gazebo/map/lab_corridor/lab_corridor.yaml
new file mode 100644
index 0000000000000000000000000000000000000000..cf376f176db1bb432d5ab92c3c4a290ad25c5ec2
--- /dev/null
+++ b/rois_2dnav_gazebo/map/lab_corridor/lab_corridor.yaml
@@ -0,0 +1,7 @@
+image: lab_corridor.pgm
+resolution: 0.050000
+origin: [-100.000000, -100.000000, 0.000000]
+negate: 0
+occupied_thresh: 0.65
+free_thresh: 0.196
+
diff --git a/rois_2dnav_gazebo/package.xml b/rois_2dnav_gazebo/package.xml
new file mode 100644
index 0000000000000000000000000000000000000000..b11e207bb49ff0a27488c0b71b4ad4aaf2630d4f
--- /dev/null
+++ b/rois_2dnav_gazebo/package.xml
@@ -0,0 +1,71 @@
+
+
+ rois_2dnav_gazebo
+ 0.0.0
+ The rois_2dnav_gazebo package
+
+
+
+
+ tanacchi
+
+
+
+
+
+ TODO
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ catkin
+ amcl
+ map_server
+ move_base
+ rois_gazebo
+ amcl
+ map_server
+ move_base
+ rois_gazebo
+ amcl
+ map_server
+ move_base
+ rois_gazebo
+
+
+
+
+
+
+
+
diff --git a/rois_2dnav_gazebo/rviz/navigation.rviz b/rois_2dnav_gazebo/rviz/navigation.rviz
new file mode 100644
index 0000000000000000000000000000000000000000..826eed877e56e25f162574de5e9cd4bb046f9432
--- /dev/null
+++ b/rois_2dnav_gazebo/rviz/navigation.rviz
@@ -0,0 +1,327 @@
+Panels:
+ - Class: rviz/Displays
+ Help Height: 85
+ Name: Displays
+ Property Tree Widget:
+ Expanded:
+ - /Global Options1
+ - /Path2
+ Splitter Ratio: 0.29716193675994873
+ Tree Height: 801
+ - Class: rviz/Selection
+ Name: Selection
+ - Class: rviz/Tool Properties
+ Expanded:
+ - /2D Pose Estimate1
+ - /2D Nav Goal1
+ - /Publish Point1
+ Name: Tool Properties
+ Splitter Ratio: 0.5886790156364441
+ - Class: rviz/Views
+ Expanded:
+ - /Current View1
+ Name: Views
+ Splitter Ratio: 0.5
+ - Class: rviz/Time
+ Experimental: false
+ Name: Time
+ SyncMode: 0
+ SyncSource: LaserScan
+Preferences:
+ PromptSaveOnExit: true
+Toolbars:
+ toolButtonStyle: 2
+Visualization Manager:
+ Class: ""
+ Displays:
+ - Alpha: 0.5
+ Cell Size: 1
+ Class: rviz/Grid
+ Color: 160; 160; 164
+ Enabled: true
+ Line Style:
+ Line Width: 0.029999999329447746
+ Value: Lines
+ Name: Grid
+ Normal Cell Count: 0
+ Offset:
+ X: 0
+ Y: 0
+ Z: 0
+ Plane: XY
+ Plane Cell Count: 10
+ Reference Frame:
+ Value: true
+ - Alpha: 0.5
+ 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
+ caster_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ left_wheel_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ lrf_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ right_wheel_link:
+ Alpha: 1
+ Show Axes: false
+ Show Trail: false
+ Value: true
+ Name: RobotModel
+ Robot Description: robot_description
+ TF Prefix: ""
+ Update Interval: 0
+ Value: true
+ Visual Enabled: true
+ - Class: rviz/TF
+ Enabled: true
+ Frame Timeout: 15
+ Frames:
+ All Enabled: true
+ base_footprint:
+ Value: true
+ base_link:
+ Value: true
+ caster_link:
+ Value: true
+ left_wheel_link:
+ Value: true
+ lrf_link:
+ Value: true
+ map:
+ Value: true
+ odom:
+ Value: true
+ right_wheel_link:
+ Value: true
+ Marker Scale: 0.5
+ Name: TF
+ Show Arrows: true
+ Show Axes: true
+ Show Names: true
+ Tree:
+ map:
+ odom:
+ base_footprint:
+ base_link:
+ {}
+ caster_link:
+ {}
+ left_wheel_link:
+ {}
+ lrf_link:
+ {}
+ right_wheel_link:
+ {}
+ 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: 0
+ Min Color: 0; 0; 0
+ Min Intensity: 0
+ Name: LaserScan
+ Position Transformer: XYZ
+ Queue Size: 10
+ Selectable: true
+ Size (Pixels): 3
+ Size (m): 0.05000000074505806
+ Style: Flat Squares
+ Topic: /scan
+ Unreliable: false
+ Use Fixed Frame: true
+ Use rainbow: true
+ Value: true
+ - Alpha: 0.699999988079071
+ Class: rviz/Map
+ Color Scheme: map
+ Draw Behind: false
+ Enabled: true
+ Name: Map
+ Topic: /map
+ Unreliable: false
+ Use Timestamp: false
+ Value: true
+ - Alpha: 0.699999988079071
+ Class: rviz/Map
+ Color Scheme: costmap
+ Draw Behind: false
+ Enabled: true
+ Name: Map
+ Topic: /move_base/local_costmap/costmap
+ Unreliable: false
+ Use Timestamp: false
+ Value: true
+ - Alpha: 1
+ Buffer Length: 1
+ Class: rviz/Path
+ Color: 25; 255; 0
+ Enabled: true
+ Head Diameter: 0.30000001192092896
+ Head Length: 0.20000000298023224
+ Length: 0.30000001192092896
+ Line Style: Lines
+ Line Width: 0.029999999329447746
+ Name: Path
+ Offset:
+ X: 0
+ Y: 0
+ Z: 0
+ Pose Color: 255; 85; 255
+ Pose Style: None
+ Radius: 0.029999999329447746
+ Shaft Diameter: 0.10000000149011612
+ Shaft Length: 0.10000000149011612
+ Topic: /move_base/GlobalPlanner/plan
+ Unreliable: false
+ Value: true
+ - Alpha: 1
+ Buffer Length: 1
+ Class: rviz/Path
+ Color: 52; 101; 164
+ Enabled: true
+ Head Diameter: 0.30000001192092896
+ Head Length: 0.20000000298023224
+ Length: 0.30000001192092896
+ Line Style: Billboards
+ Line Width: 0.029999999329447746
+ Name: Path
+ Offset:
+ X: 0
+ Y: 0
+ Z: 0
+ Pose Color: 255; 85; 255
+ Pose Style: None
+ Radius: 0.029999999329447746
+ Shaft Diameter: 0.10000000149011612
+ Shaft Length: 0.10000000149011612
+ Topic: /move_base/TrajectoryPlannerROS/local_plan
+ Unreliable: false
+ Value: true
+ - Alpha: 1
+ Class: rviz/Polygon
+ Color: 25; 255; 0
+ Enabled: true
+ Name: Polygon
+ Topic: /move_base/local_costmap/footprint
+ Unreliable: false
+ Value: true
+ - Alpha: 1
+ Arrow Length: 0.30000001192092896
+ Axes Length: 0.30000001192092896
+ Axes Radius: 0.009999999776482582
+ Class: rviz/PoseArray
+ Color: 255; 25; 0
+ Enabled: true
+ Head Length: 0.07000000029802322
+ Head Radius: 0.029999999329447746
+ Name: PoseArray
+ Shaft Length: 0.23000000417232513
+ Shaft Radius: 0.009999999776482582
+ Shape: Arrow (Flat)
+ Topic: /particlecloud
+ Unreliable: false
+ Value: true
+ 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
+ Theta std deviation: 0.2617993950843811
+ Topic: /initialpose
+ X std deviation: 0.5
+ Y std deviation: 0.5
+ - Class: rviz/SetGoal
+ Topic: /move_base_simple/goal
+ - Class: rviz/PublishPoint
+ Single click: true
+ Topic: /clicked_point
+ Value: true
+ Views:
+ Current:
+ Class: rviz/Orbit
+ Distance: 23.120027542114258
+ Enable Stereo Rendering:
+ Stereo Eye Separation: 0.05999999865889549
+ Stereo Focal Distance: 1
+ Swap Stereo Eyes: false
+ Value: false
+ Focal Point:
+ X: 2.620417356491089
+ Y: -0.4015696048736572
+ Z: -3.6895456314086914
+ Focal Shape Fixed Size: true
+ Focal Shape Size: 0.05000000074505806
+ Invert Z Axis: false
+ Name: Current View
+ Near Clip Distance: 0.009999999776482582
+ Pitch: 0.9997971057891846
+ Target Frame:
+ Value: Orbit (rviz)
+ Yaw: 3.158579111099243
+ Saved: ~
+Window Geometry:
+ Displays:
+ collapsed: false
+ Height: 1136
+ Hide Left Dock: false
+ Hide Right Dock: false
+ QMainWindow State: 000000ff00000000fd00000004000000000000020a000003bdfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006e00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730000000047000003bd000000f100fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002bffc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000047000002bf000000c200fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000039f00000044fc0100000002fb0000000800540069006d006501000000000000039f0000037100fffffffb0000000800540069006d006501000000000000045000000000000000000000039f000003bd00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+ Selection:
+ collapsed: false
+ Time:
+ collapsed: false
+ Tool Properties:
+ collapsed: false
+ Views:
+ collapsed: false
+ Width: 927
+ X: 67
+ Y: 34
diff --git a/rois_bringup/CMakeLists.txt b/rois_bringup/CMakeLists.txt
new file mode 100644
index 0000000000000000000000000000000000000000..9be0d8360430a0c3fa1c18f64aab40735c112d44
--- /dev/null
+++ b/rois_bringup/CMakeLists.txt
@@ -0,0 +1,206 @@
+cmake_minimum_required(VERSION 2.8.3)
+project(rois_bringup)
+
+## 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 COMPONENTS
+ rois_2dnav_gazebo
+ rois_description
+ rois_gazebo
+)
+
+## 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 rois_bringup
+# CATKIN_DEPENDS rois_2dnav_gazebo rois_description rois_gazebo
+# 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}/rois_bringup.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/rois_bringup_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 for installation
+## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
+# install(TARGETS ${PROJECT_NAME}_node
+# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
+# )
+
+## Mark libraries for installation
+## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
+# install(TARGETS ${PROJECT_NAME}
+# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
+# RUNTIME DESTINATION ${CATKIN_GLOBAL_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_rois_bringup.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)
diff --git a/rois_bringup/launch/navigation.launch b/rois_bringup/launch/navigation.launch
new file mode 100644
index 0000000000000000000000000000000000000000..81c97bfead1772800411708f2e748d5e7afb3606
--- /dev/null
+++ b/rois_bringup/launch/navigation.launch
@@ -0,0 +1,18 @@
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/rois_bringup/package.xml b/rois_bringup/package.xml
new file mode 100644
index 0000000000000000000000000000000000000000..7e6a9008bbfeaeacc7a51c798e90bd208ee688ed
--- /dev/null
+++ b/rois_bringup/package.xml
@@ -0,0 +1,68 @@
+
+
+ rois_bringup
+ 0.0.0
+ The rois_bringup package
+
+
+
+
+ tanacchi
+
+
+
+
+
+ TODO
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ catkin
+ rois_2dnav_gazebo
+ rois_description
+ rois_gazebo
+ rois_2dnav_gazebo
+ rois_description
+ rois_gazebo
+ rois_2dnav_gazebo
+ rois_description
+ rois_gazebo
+
+
+
+
+
+
+
+
diff --git a/rois_description/robot/roisbot.urdf.xacro b/rois_description/robot/roisbot.urdf.xacro
index 1cd1805627180676152124ed306458a0eb13a5a2..b201f413dceede53369518817832a06dacef9c7e 100644
--- a/rois_description/robot/roisbot.urdf.xacro
+++ b/rois_description/robot/roisbot.urdf.xacro
@@ -1,11 +1,11 @@
-
-
+
+
-
-
+
+
@@ -182,7 +182,7 @@
- 0.50
+ 0.20
131
0.01
diff --git a/rois_gazebo/config/controller.yaml b/rois_gazebo/config/controller.yaml
index e0b2f753024e9364be5fee0d73d59f67b3c1b380..d9ae17569223d3b43dbd0401a78a5e9910490d94 100644
--- a/rois_gazebo/config/controller.yaml
+++ b/rois_gazebo/config/controller.yaml
@@ -13,8 +13,8 @@ roisbot:
# Wheel separation and diameter. These are both optional.
# diff_drive_controller will attempt to read either one or both from the
# URDF if not specified as a parameter
- wheel_separation : 0.7
- wheel_radius : 0.2
+ wheel_separation : 0.3
+ wheel_radius : 0.1
# Wheel separation and radius multipliers
wheel_separation_multiplier: 1.0 # default: 1.0