├── README.md
└── navros_pkg
├── CMakeLists.txt
├── launch
├── amcl.launch
├── gmapping.launch
├── move_base.launch
├── octomap.launch
├── pctl.launch
├── spawn_car.launch
├── spawn_world.launch
├── urdf_gazebo_view.launch
└── urdf_rviz_view.launch
├── maps
├── map.pgm
└── map.yaml
├── package.xml
├── param
├── costmap_common_params.yaml
├── dwa_local_planner_params.yaml
├── global_costmap_params.yaml
├── local_costmap_params.yaml
├── move_base_params.yaml
└── navfn_global_planner_params.yaml
├── rviz
├── kinect.rviz
├── laser.rviz
├── map.rviz
├── navigate.rviz
└── octomap.rviz
├── screenshots
├── grid_slam.jpg
├── grid_slam.png
├── navigation.png
└── small_house.png
└── urdf
├── car.urdf.xacro
└── gazebo_plugins.urdf.xacro
/README.md:
--------------------------------------------------------------------------------
1 | Autonomous SLAM using a differential drive robot.
2 | This work is a project for *Introduction to Robotics* class.
3 |
4 | # Overview
5 | There are two videos showing the whole setup in action: [Building a map of the environment | ROS Gmapping | Octomap](https://youtu.be/mLMfofIn_PM) and [Autonomous Robot navigation using the ROS Navigation](https://youtu.be/94Ar3pGP3KM).
6 |
7 | # Prerequisites
8 |
9 | This project was developed for ROS Noetic (Ubuntu 20.04). The following
10 | packages are required:
11 | 1. [pointcloud_to_laserscan package](http://wiki.ros.org/pointcloud_to_laserscan), is used to convert a 3D Point Cloud into a 2D laser scan, this can be installed using: `sudo apt install ros-noetic-pointcloud-to-laserscan ros-noetic-rosbridge-server`
12 | 2. To control the robot, you might need to install the [teleop_twist_keyboard package](http://wiki.ros.org/teleop_twist_keyboard) and then run teleop_twist_keyboard teleop_twist_keyboard.py.
13 | 3. [OctoMap](http://wiki.ros.org/octomap) is used to generate the 3D occupancy
14 | grid. `octomap_server` is used to interface OctoMap with ROS, both can be
15 | installed via `apt` as `ros-noetic-octomap` and `ros-noetic-octomap-ros`.
16 |
17 | 4. You'll need to install the [OctoMap RViz
18 | plugin](https://github.com/OctoMap/octomap_rviz_plugins) via `apt` as
19 | `ros-noetic-octomap-rviz-plugins`. Without it, occupancy grid
20 | visualisations in RViz will not work.
21 | 5. You will also need to install the controller_manager package: `sudo apt-get install ros-noetic-controller-manager`
22 | 6. The probabilistic localization system *amcl* is also needed, you can install it with: `sudo apt install ros-noetic-amcl`
23 |
24 | #### Note: you might need to install more packages depending on what you have previously installed, if you have any problem just google it, and install the package needed.
25 |
26 | # Usage
27 | 1. Make sure you have the prerequisites installed.
28 | 2. Clone this repo into your [catkin workspace](http://wiki.ros.org/catkin/Tutorials/create_a_workspace), e.g.
29 | into `~/catkin_ws/src/navros_pkg/`.
30 | 3. Clone [aws-robomaker-small-house-world](https://github.com/aws-robotics/aws-robomaker-small-house-world) repo into your catkin workspace, e.g.
31 | into `~/catkin_ws/src/small-house-world/`.
32 | * Add the following to your launch file:
33 | ```xml
34 |
35 |
36 |
37 | ...
38 |
39 | ```
40 | 
41 |
42 | 4. Source your ROS in the Bash instance: `source
43 | /opt/ros/noetic/setup.bash` and `source ~/catkin_ws/devel/setup.bash`.
44 | 5. Run `catkin_make` in `~/catkin_ws/` and `source
45 | ~/catkin_ws/devel/setup.bash` again.
46 |
47 | ## Start Gazebo Simulation
48 | 6. Start the simulation using: `roslaunch aws_robomaker_small_house_world view_small_house.launch`.
49 | 7. Spawn the robot in the map using: `roslaunch navros_pkg urdf_gazebo_view.launch`.
50 | Keep this terminal running for all the next steps.
51 |
52 | ## Mapping
53 | 3D occupancy grid map | 2D occupancy grid map
54 | :-------------------------:|:-------------------------:
55 |  | 
56 |
57 | 8. Run the gmapping SLAM command:`roslaunch navros_pkg gmapping.launch`
58 | 9. Navigate to rviz folder using:`cd catkin_ws/src/navros_pkg/rviz` then run it using: `rviz -d map.rviz`
59 | 10. For OCTOMAP use:`roslaunch navros_pkg octomap.launch`
60 | Then navigate to rviz folder using:`cd catkin_ws/src/navros_pkg/rviz` then run it using: `rviz -d octomap.rviz`
61 | 11. To control the drone manually, you use: `rosrun teleop_twist_keyboard teleop_twist_keyboard.py` but it requires [teleop_twist_keyboard](http://wiki.ros.org/teleop_twist_keyboard) package to be installed.
62 | 12. Once mapping is complete, Save the map: `rosrun map_server map_saver ~/catkin_ws/src/navros_pkg/maps/name_of_map`
63 | if this command is not working for some reason, then run this `rosrun map_server map_saver` then copy the map generated in *src* directory to *~/catkin_ws/src/navros_pkg/maps/* directory.
64 | Finally close everything, and relaunch gazebo only with the robot (repeat steps 6 and 7).
65 |
66 | ## Autonomous Navigation
67 | 
68 |
69 | 13. To start the navigation using the previously generated map, run each of the following commands in a new terminal:
70 | * A) `roslaunch navros_pkg amcl.launch map:='name_of_map'` if you picked a name for your map make sure to change *name_of_map* otherwise it should be *map* (check the name in the maps folder).
71 | * B) `roslaunch navros_pkg move_base.launch`
72 | * C) `cd catkin_ws/src/navros_pkg/rviz` then `rviz -d navigate.rviz`
73 |
74 | 14. Test navigation using rviz:
75 | * Set initial pose (Click "2D pose estimate" and pinpoint the approximate location of robot on map).*
76 | * Red arrows indicate the probable location.
77 | * Set goal for the robot in RVIZ (Click "2D Nav goal" and pinpoint the desired goal on the map).
78 | * Green line indicates the path planned.
79 |
80 | 15. Thanks and PROFIT
81 |
82 |
83 |
84 |
--------------------------------------------------------------------------------
/navros_pkg/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 2.8.3)
2 | project(navros_pkg)
3 |
4 | ## Compile as C++11, supported in ROS Kinetic and newer
5 | # add_compile_options(-std=c++11)
6 |
7 | ## Find catkin macros and libraries
8 | ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
9 | ## is used, also find other catkin packages
10 | find_package(catkin REQUIRED COMPONENTS
11 | controller_manager
12 | gazebo_ros
13 | joint_state_publisher
14 | robot_state_publisher
15 | rospy
16 | rviz
17 | urdf
18 | )
19 |
20 | ## System dependencies are found with CMake's conventions
21 | # find_package(Boost REQUIRED COMPONENTS system)
22 |
23 |
24 | ## Uncomment this if the package has a setup.py. This macro ensures
25 | ## modules and global scripts declared therein get installed
26 | ## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
27 | # catkin_python_setup()
28 |
29 | ################################################
30 | ## Declare ROS messages, services and actions ##
31 | ################################################
32 |
33 | ## To declare and build messages, services or actions from within this
34 | ## package, follow these steps:
35 | ## * Let MSG_DEP_SET be the set of packages whose message types you use in
36 | ## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
37 | ## * In the file package.xml:
38 | ## * add a build_depend tag for "message_generation"
39 | ## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
40 | ## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
41 | ## but can be declared for certainty nonetheless:
42 | ## * add a exec_depend tag for "message_runtime"
43 | ## * In this file (CMakeLists.txt):
44 | ## * add "message_generation" and every package in MSG_DEP_SET to
45 | ## find_package(catkin REQUIRED COMPONENTS ...)
46 | ## * add "message_runtime" and every package in MSG_DEP_SET to
47 | ## catkin_package(CATKIN_DEPENDS ...)
48 | ## * uncomment the add_*_files sections below as needed
49 | ## and list every .msg/.srv/.action file to be processed
50 | ## * uncomment the generate_messages entry below
51 | ## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
52 |
53 | ## Generate messages in the 'msg' folder
54 | # add_message_files(
55 | # FILES
56 | # Message1.msg
57 | # Message2.msg
58 | # )
59 |
60 | ## Generate services in the 'srv' folder
61 | # add_service_files(
62 | # FILES
63 | # Service1.srv
64 | # Service2.srv
65 | # )
66 |
67 | ## Generate actions in the 'action' folder
68 | # add_action_files(
69 | # FILES
70 | # Action1.action
71 | # Action2.action
72 | # )
73 |
74 | ## Generate added messages and services with any dependencies listed here
75 | # generate_messages(
76 | # DEPENDENCIES
77 | # std_msgs # Or other packages containing msgs
78 | # )
79 |
80 | ################################################
81 | ## Declare ROS dynamic reconfigure parameters ##
82 | ################################################
83 |
84 | ## To declare and build dynamic reconfigure parameters within this
85 | ## package, follow these steps:
86 | ## * In the file package.xml:
87 | ## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
88 | ## * In this file (CMakeLists.txt):
89 | ## * add "dynamic_reconfigure" to
90 | ## find_package(catkin REQUIRED COMPONENTS ...)
91 | ## * uncomment the "generate_dynamic_reconfigure_options" section below
92 | ## and list every .cfg file to be processed
93 |
94 | ## Generate dynamic reconfigure parameters in the 'cfg' folder
95 | # generate_dynamic_reconfigure_options(
96 | # cfg/DynReconf1.cfg
97 | # cfg/DynReconf2.cfg
98 | # )
99 |
100 | ###################################
101 | ## catkin specific configuration ##
102 | ###################################
103 | ## The catkin_package macro generates cmake config files for your package
104 | ## Declare things to be passed to dependent projects
105 | ## INCLUDE_DIRS: uncomment this if your package contains header files
106 | ## LIBRARIES: libraries you create in this project that dependent projects also need
107 | ## CATKIN_DEPENDS: catkin_packages dependent projects also need
108 | ## DEPENDS: system dependencies of this project that dependent projects also need
109 | catkin_package(
110 | # INCLUDE_DIRS include
111 | # LIBRARIES navros_pkg
112 | # CATKIN_DEPENDS controller_manager gazebo_ros joint_state_publisher robot_state_publisher rospy rviz urdf
113 | # DEPENDS system_lib
114 | )
115 |
116 | ###########
117 | ## Build ##
118 | ###########
119 |
120 | ## Specify additional locations of header files
121 | ## Your package locations should be listed before other locations
122 | include_directories(
123 | # include
124 | ${catkin_INCLUDE_DIRS}
125 | )
126 |
127 | ## Declare a C++ library
128 | # add_library(${PROJECT_NAME}
129 | # src/${PROJECT_NAME}/navros_pkg.cpp
130 | # )
131 |
132 | ## Add cmake target dependencies of the library
133 | ## as an example, code may need to be generated before libraries
134 | ## either from message generation or dynamic reconfigure
135 | # add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
136 |
137 | ## Declare a C++ executable
138 | ## With catkin_make all packages are built within a single CMake context
139 | ## The recommended prefix ensures that target names across packages don't collide
140 | # add_executable(${PROJECT_NAME}_node src/navros_pkg_node.cpp)
141 |
142 | ## Rename C++ executable without prefix
143 | ## The above recommended prefix causes long target names, the following renames the
144 | ## target back to the shorter version for ease of user use
145 | ## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
146 | # set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
147 |
148 | ## Add cmake target dependencies of the executable
149 | ## same as for the library above
150 | # add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
151 |
152 | ## Specify libraries to link a library or executable target against
153 | # target_link_libraries(${PROJECT_NAME}_node
154 | # ${catkin_LIBRARIES}
155 | # )
156 |
157 | #############
158 | ## Install ##
159 | #############
160 |
161 | # all install targets should use catkin DESTINATION variables
162 | # See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
163 |
164 | ## Mark executable scripts (Python etc.) for installation
165 | ## in contrast to setup.py, you can choose the destination
166 | # install(PROGRAMS
167 | # scripts/my_python_script
168 | # DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
169 | # )
170 |
171 | ## Mark executables and/or libraries for installation
172 | # install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
173 | # ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
174 | # LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
175 | # RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
176 | # )
177 |
178 | ## Mark cpp header files for installation
179 | # install(DIRECTORY include/${PROJECT_NAME}/
180 | # DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
181 | # FILES_MATCHING PATTERN "*.h"
182 | # PATTERN ".svn" EXCLUDE
183 | # )
184 |
185 | ## Mark other files for installation (e.g. launch and bag files, etc.)
186 | # install(FILES
187 | # # myfile1
188 | # # myfile2
189 | # DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
190 | # )
191 |
192 | #############
193 | ## Testing ##
194 | #############
195 |
196 | ## Add gtest based cpp test target and link libraries
197 | # catkin_add_gtest(${PROJECT_NAME}-test test/test_navros_pkg.cpp)
198 | # if(TARGET ${PROJECT_NAME}-test)
199 | # target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
200 | # endif()
201 |
202 | ## Add folders to be run by python nosetests
203 | # catkin_add_nosetests(test)
204 |
--------------------------------------------------------------------------------
/navros_pkg/launch/amcl.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
--------------------------------------------------------------------------------
/navros_pkg/launch/gmapping.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
--------------------------------------------------------------------------------
/navros_pkg/launch/move_base.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
--------------------------------------------------------------------------------
/navros_pkg/launch/octomap.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
--------------------------------------------------------------------------------
/navros_pkg/launch/pctl.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 | target_frame: chassis # Leave disabled to output scan in pointcloud frame
12 | transform_tolerance: 0.01
13 | min_height: 0.0
14 | max_height: 1.0
15 |
16 | angle_min: -1.5708 # -M_PI/2
17 | angle_max: 1.5708 # M_PI/2
18 | angle_increment: 0.0087 # M_PI/360.0
19 | scan_time: 0.3333
20 | range_min: 0.45
21 | range_max: 4.0
22 | use_inf: true
23 | inf_epsilon: 1.0
24 |
25 | # Concurrency level, affects number of pointclouds queued for processing and number of threads used
26 | # 0 : Detect number of cores
27 | # 1 : Single threaded
28 | # 2->inf : Parallelism level
29 | concurrency_level: 1
30 |
31 |
32 |
33 |
34 |
35 |
--------------------------------------------------------------------------------
/navros_pkg/launch/spawn_car.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
--------------------------------------------------------------------------------
/navros_pkg/launch/spawn_world.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | ...
5 |
6 |
--------------------------------------------------------------------------------
/navros_pkg/launch/urdf_gazebo_view.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
--------------------------------------------------------------------------------
/navros_pkg/launch/urdf_rviz_view.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
--------------------------------------------------------------------------------
/navros_pkg/maps/map.pgm:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/morou34/Navigation-of-an-Autonomous-Differential-Drive-Robot/949e3d187e54dd3ab9ba951b77cecd9f45a44412/navros_pkg/maps/map.pgm
--------------------------------------------------------------------------------
/navros_pkg/maps/map.yaml:
--------------------------------------------------------------------------------
1 | image: map.pgm
2 | resolution: 0.050000
3 | origin: [-12.200000, -15.400000, 0.000000]
4 | negate: 0
5 | occupied_thresh: 0.65
6 | free_thresh: 0.196
7 |
8 |
--------------------------------------------------------------------------------
/navros_pkg/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | navros_pkg
4 | 0.0.0
5 | The navros_pkg package
6 |
7 |
8 |
9 |
10 | yug
11 |
12 | TODO
13 |
14 |
15 | catkin
16 | controller_manager
17 | gazebo_ros
18 | joint_state_publisher
19 | robot_state_publisher
20 | rospy
21 | rviz
22 | urdf
23 | controller_manager
24 | gazebo_ros
25 | joint_state_publisher
26 | robot_state_publisher
27 | rospy
28 | rviz
29 | urdf
30 | controller_manager
31 | gazebo_ros
32 | joint_state_publisher
33 | robot_state_publisher
34 | rospy
35 | rviz
36 | urdf
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
--------------------------------------------------------------------------------
/navros_pkg/param/costmap_common_params.yaml:
--------------------------------------------------------------------------------
1 |
2 | footprint: [[-0.3, -0.2], [-0.3, 0.2], [0.3, 0.2], [0.3, -0.2]]
3 |
4 | obstacle_layer:
5 | enabled: true
6 | max_obstacle_height: 0.6
7 | obstacle_range: 2.5
8 | raytrace_range: 3.0
9 | observation_sources: scan
10 | scan:
11 | data_type: LaserScan
12 | topic: scan
13 | marking: true
14 | clearing: true
15 | min_obstacle_height: 0.25
16 | max_obstacle_height: 0.35
17 |
18 |
19 | inflation_layer:
20 | enabled: true
21 | cost_scaling_factor: 5.0
22 | inflation_radius: 0.5
23 |
24 | static_layer:
25 | enabled: true
26 |
27 |
28 |
--------------------------------------------------------------------------------
/navros_pkg/param/dwa_local_planner_params.yaml:
--------------------------------------------------------------------------------
1 | DWAPlannerROS:
2 |
3 | # Robot Configuration Parameters
4 | max_vel_x: 0.5 # 0.55
5 | min_vel_x: 0.0
6 |
7 | max_vel_y: 0.0 # diff drive robot
8 | min_vel_y: 0.0 # diff drive robot
9 |
10 | max_trans_vel: 0.5 # choose slightly less than the base's capability
11 | min_trans_vel: 0.1 # this is the min trans velocity when there is negligible rotational velocity
12 | trans_stopped_vel: 0.1
13 |
14 |
15 | max_rot_vel: 5.0 # choose slightly less than the base's capability
16 | min_rot_vel: 0.4 # this is the min angular velocity when there is negligible translational velocity
17 | rot_stopped_vel: 0.4
18 |
19 | acc_lim_x: 1.0 # maximum is theoretically 2.0, but we
20 | acc_lim_theta: 2.0
21 | acc_lim_y: 0.0 # diff drive robot
22 |
23 | # Goal Tolerance Parameters
24 | yaw_goal_tolerance: 0.3 # 0.05
25 | xy_goal_tolerance: 0.15 # 0.10
26 | # latch_xy_goal_tolerance: false
27 |
28 | # Forward Simulation Parameters
29 | sim_time: 1.0 # 1.7
30 | vx_samples: 6 # 3
31 | vy_samples: 1 # diff drive robot, there is only one sample
32 | vtheta_samples: 20 # 20
33 |
34 | # Trajectory Scoring Parameters
35 | path_distance_bias: 64.0 # 32.0 - weighting for how much it should stick to the global path plan
36 | goal_distance_bias: 24.0 # 24.0 - wighting for how much it should attempt to reach its goal
37 | occdist_scale: 0.5 # 0.01 - weighting for how much the controller should avoid obstacles
38 | forward_point_distance: 0.325 # 0.325 - how far along to place an additional scoring point
39 | stop_time_buffer: 0.2 # 0.2 - amount of time a robot must stop in before colliding for a valid traj.
40 | scaling_speed: 0.25 # 0.25 - absolute velocity at which to start scaling the robot's footprint
41 | max_scaling_factor: 0.2 # 0.2 - how much to scale the robot's footprint when at speed.
42 |
43 | # Oscillation Prevention Parameters
44 | oscillation_reset_dist: 0.05 # 0.05 - how far to travel before resetting oscillation flags
45 |
46 | # Debugging
47 | publish_traj_pc : true
48 | publish_cost_grid_pc: true
49 | global_frame_id: odom
50 |
51 |
--------------------------------------------------------------------------------
/navros_pkg/param/global_costmap_params.yaml:
--------------------------------------------------------------------------------
1 | global_costmap:
2 | global_frame: /map
3 | static_map: true
4 | rolling_window: false
5 | plugins:
6 | - {name: static_layer, type: "costmap_2d::StaticLayer"}
7 | - {name: obstacle_layer, type: "costmap_2d::VoxelLayer"}
8 | - {name: inflation_layer, type: "costmap_2d::InflationLayer"}
9 |
10 |
--------------------------------------------------------------------------------
/navros_pkg/param/local_costmap_params.yaml:
--------------------------------------------------------------------------------
1 | local_costmap:
2 | global_frame: odom
3 | robot_base_frame: /base_footprint
4 | update_frequency: 5.0
5 | publish_frequency: 2.0
6 | static_map: false
7 | rolling_window: true
8 | width: 4.0
9 | height: 4.0
10 | plugins:
11 | - {name: obstacle_layer, type: "costmap_2d::ObstacleLayer"}
12 | - {name: inflation_layer, type: "costmap_2d::InflationLayer"}
13 |
--------------------------------------------------------------------------------
/navros_pkg/param/move_base_params.yaml:
--------------------------------------------------------------------------------
1 | # Move base node parameters. For full documentation of the parameters in this file, please see
2 | #
3 | # http://www.ros.org/wiki/move_base
4 | #
5 | shutdown_costmaps: false
6 |
7 | controller_frequency: 5.0
8 | controller_patience: 3.0
9 |
10 |
11 | planner_frequency: 1.0
12 | planner_patience: 5.0
13 |
14 | oscillation_timeout: 10.0
15 | oscillation_distance: 0.2
16 |
17 |
18 | base_local_planner: "dwa_local_planner/DWAPlannerROS"
19 | base_global_planner: "navfn/NavfnROS"
20 |
21 |
22 | recovery_behavior_enabled: true
23 |
24 |
25 |
--------------------------------------------------------------------------------
/navros_pkg/param/navfn_global_planner_params.yaml:
--------------------------------------------------------------------------------
1 |
2 | NavfnROS:
3 | visualize_potential: false #Publish potential for rviz as pointcloud2, not really helpful, default false
4 | allow_unknown: false #Specifies whether or not to allow navfn to create plans that traverse unknown space, default true
5 | #Needs to have track_unknown_space: true in the obstacle / voxel layer (in costmap_commons_param) to work
6 | planner_window_x: 0.0 #Specifies the x size of an optional window to restrict the planner to, default 0.0
7 | planner_window_y: 0.0 #Specifies the y size of an optional window to restrict the planner to, default 0.0
8 |
9 | default_tolerance: 1.0 #If the goal is in an obstacle, the planer will plan to the nearest point in the radius of default_tolerance, default 0.0
10 | #The area is always searched, so could be slow for big values
11 |
--------------------------------------------------------------------------------
/navros_pkg/rviz/kinect.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz/Displays
3 | Help Height: 78
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /Global Options1
8 | - /Status1
9 | Splitter Ratio: 0.5
10 | Tree Height: 454
11 | - Class: rviz/Selection
12 | Name: Selection
13 | - Class: rviz/Tool Properties
14 | Expanded:
15 | - /2D Pose Estimate1
16 | - /2D Nav Goal1
17 | - /Publish Point1
18 | Name: Tool Properties
19 | Splitter Ratio: 0.588679016
20 | - Class: rviz/Views
21 | Expanded:
22 | - /Current View1
23 | Name: Views
24 | Splitter Ratio: 0.5
25 | - Class: rviz/Time
26 | Experimental: false
27 | Name: Time
28 | SyncMode: 0
29 | SyncSource: PointCloud2
30 | Visualization Manager:
31 | Class: ""
32 | Displays:
33 | - Alpha: 0.5
34 | Cell Size: 1
35 | Class: rviz/Grid
36 | Color: 160; 160; 164
37 | Enabled: true
38 | Line Style:
39 | Line Width: 0.0299999993
40 | Value: Lines
41 | Name: Grid
42 | Normal Cell Count: 0
43 | Offset:
44 | X: 0
45 | Y: 0
46 | Z: 0
47 | Plane: XY
48 | Plane Cell Count: 10
49 | Reference Frame:
50 | Value: true
51 | - Alpha: 1
52 | Class: rviz/RobotModel
53 | Collision Enabled: false
54 | Enabled: true
55 | Links:
56 | All Links Enabled: true
57 | Expand Joint Details: false
58 | Expand Link Details: false
59 | Expand Tree: false
60 | Link Tree Style: Links in Alphabetic Order
61 | chassis:
62 | Alpha: 1
63 | Show Axes: false
64 | Show Trail: false
65 | Value: true
66 | kinect:
67 | Alpha: 1
68 | Show Axes: false
69 | Show Trail: false
70 | Value: true
71 | kinect_link:
72 | Alpha: 1
73 | Show Axes: false
74 | Show Trail: false
75 | left_wheel:
76 | Alpha: 1
77 | Show Axes: false
78 | Show Trail: false
79 | Value: true
80 | right_wheel:
81 | Alpha: 1
82 | Show Axes: false
83 | Show Trail: false
84 | Value: true
85 | Name: RobotModel
86 | Robot Description: robot_description
87 | TF Prefix: ""
88 | Update Interval: 0
89 | Value: true
90 | Visual Enabled: true
91 | - Class: rviz/TF
92 | Enabled: true
93 | Frame Timeout: 15
94 | Frames:
95 | All Enabled: true
96 | chassis:
97 | Value: true
98 | kinect:
99 | Value: true
100 | kinect_link:
101 | Value: true
102 | left_wheel:
103 | Value: true
104 | odom:
105 | Value: true
106 | right_wheel:
107 | Value: true
108 | Marker Scale: 1
109 | Name: TF
110 | Show Arrows: true
111 | Show Axes: true
112 | Show Names: true
113 | Tree:
114 | odom:
115 | chassis:
116 | kinect:
117 | {}
118 | kinect_link:
119 | {}
120 | left_wheel:
121 | {}
122 | right_wheel:
123 | {}
124 | Update Interval: 0
125 | Value: true
126 | - Alpha: 1
127 | Autocompute Intensity Bounds: true
128 | Autocompute Value Bounds:
129 | Max Value: 10
130 | Min Value: -10
131 | Value: true
132 | Axis: Z
133 | Channel Name: intensity
134 | Class: rviz/PointCloud2
135 | Color: 255; 255; 255
136 | Color Transformer: RGB8
137 | Decay Time: 0
138 | Enabled: true
139 | Invert Rainbow: false
140 | Max Color: 255; 255; 255
141 | Max Intensity: 4096
142 | Min Color: 0; 0; 0
143 | Min Intensity: 0
144 | Name: PointCloud2
145 | Position Transformer: XYZ
146 | Queue Size: 10
147 | Selectable: true
148 | Size (Pixels): 3
149 | Size (m): 0.00999999978
150 | Style: Flat Squares
151 | Topic: /kinect/depth/points
152 | Unreliable: false
153 | Use Fixed Frame: true
154 | Use rainbow: true
155 | Value: true
156 | - Class: rviz/Camera
157 | Enabled: true
158 | Image Rendering: background and overlay
159 | Image Topic: /kinect/rgb/image_raw
160 | Name: Camera
161 | Overlay Alpha: 0.5
162 | Queue Size: 2
163 | Transport Hint: raw
164 | Unreliable: false
165 | Value: true
166 | Visibility:
167 | Grid: true
168 | PointCloud2: true
169 | RobotModel: true
170 | TF: true
171 | Value: true
172 | Zoom Factor: 1
173 | Enabled: true
174 | Global Options:
175 | Background Color: 48; 48; 48
176 | Default Light: true
177 | Fixed Frame: odom
178 | Frame Rate: 30
179 | Name: root
180 | Tools:
181 | - Class: rviz/Interact
182 | Hide Inactive Objects: true
183 | - Class: rviz/MoveCamera
184 | - Class: rviz/Select
185 | - Class: rviz/FocusCamera
186 | - Class: rviz/Measure
187 | - Class: rviz/SetInitialPose
188 | Topic: /initialpose
189 | - Class: rviz/SetGoal
190 | Topic: /move_base_simple/goal
191 | - Class: rviz/PublishPoint
192 | Single click: true
193 | Topic: /clicked_point
194 | Value: true
195 | Views:
196 | Current:
197 | Class: rviz/Orbit
198 | Distance: 6.43286276
199 | Enable Stereo Rendering:
200 | Stereo Eye Separation: 0.0599999987
201 | Stereo Focal Distance: 1
202 | Swap Stereo Eyes: false
203 | Value: false
204 | Focal Point:
205 | X: -0.28541708
206 | Y: -0.0437853597
207 | Z: -0.0722417384
208 | Focal Shape Fixed Size: true
209 | Focal Shape Size: 0.0500000007
210 | Invert Z Axis: false
211 | Name: Current View
212 | Near Clip Distance: 0.00999999978
213 | Pitch: 0.544796765
214 | Target Frame:
215 | Value: Orbit (rviz)
216 | Yaw: 1.67540514
217 | Saved: ~
218 | Window Geometry:
219 | Camera:
220 | collapsed: false
221 | Displays:
222 | collapsed: false
223 | Height: 1056
224 | Hide Left Dock: false
225 | Hide Right Dock: true
226 | QMainWindow State: 000000ff00000000fd00000004000000000000018d00000388fc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006600fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000260000000e200fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d006500720061000000021f000000bf0000000000000000fb0000000c00430061006d00650072006101000002b8000000f80000000000000000fb0000000c00430061006d006500720061010000028e000001220000001b00ffffff000000010000011e00000231fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000231000000be00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073500000046fc0100000002fb0000000800540069006d0065010000000000000735000003cc00fffffffb0000000800540069006d00650100000000000004500000000000000000000005a20000038800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
227 | Selection:
228 | collapsed: false
229 | Time:
230 | collapsed: false
231 | Tool Properties:
232 | collapsed: false
233 | Views:
234 | collapsed: true
235 | Width: 1845
236 | X: 75
237 | Y: 24
238 |
--------------------------------------------------------------------------------
/navros_pkg/rviz/laser.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz/Displays
3 | Help Height: 78
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /Global Options1
8 | Splitter Ratio: 0.5
9 | Tree Height: 750
10 | - Class: rviz/Selection
11 | Name: Selection
12 | - Class: rviz/Tool Properties
13 | Expanded:
14 | - /2D Pose Estimate1
15 | - /2D Nav Goal1
16 | - /Publish Point1
17 | Name: Tool Properties
18 | Splitter Ratio: 0.588679016
19 | - Class: rviz/Views
20 | Expanded:
21 | - /Current View1
22 | Name: Views
23 | Splitter Ratio: 0.5
24 | - Class: rviz/Time
25 | Experimental: false
26 | Name: Time
27 | SyncMode: 0
28 | SyncSource: LaserScan
29 | Visualization Manager:
30 | Class: ""
31 | Displays:
32 | - Alpha: 0.5
33 | Cell Size: 1
34 | Class: rviz/Grid
35 | Color: 160; 160; 164
36 | Enabled: true
37 | Line Style:
38 | Line Width: 0.0299999993
39 | Value: Lines
40 | Name: Grid
41 | Normal Cell Count: 0
42 | Offset:
43 | X: 0
44 | Y: 0
45 | Z: 0
46 | Plane: XY
47 | Plane Cell Count: 10
48 | Reference Frame:
49 | Value: true
50 | - Alpha: 1
51 | Class: rviz/RobotModel
52 | Collision Enabled: false
53 | Enabled: true
54 | Links:
55 | All Links Enabled: true
56 | Expand Joint Details: false
57 | Expand Link Details: false
58 | Expand Tree: false
59 | Link Tree Style: Links in Alphabetic Order
60 | chassis:
61 | Alpha: 1
62 | Show Axes: false
63 | Show Trail: false
64 | Value: true
65 | kinect:
66 | Alpha: 1
67 | Show Axes: false
68 | Show Trail: false
69 | Value: true
70 | kinect_link:
71 | Alpha: 1
72 | Show Axes: false
73 | Show Trail: false
74 | left_wheel:
75 | Alpha: 1
76 | Show Axes: false
77 | Show Trail: false
78 | Value: true
79 | right_wheel:
80 | Alpha: 1
81 | Show Axes: false
82 | Show Trail: false
83 | Value: true
84 | Name: RobotModel
85 | Robot Description: robot_description
86 | TF Prefix: ""
87 | Update Interval: 0
88 | Value: true
89 | Visual Enabled: true
90 | - Class: rviz/TF
91 | Enabled: true
92 | Frame Timeout: 15
93 | Frames:
94 | All Enabled: true
95 | chassis:
96 | Value: true
97 | kinect:
98 | Value: true
99 | kinect_link:
100 | Value: true
101 | left_wheel:
102 | Value: true
103 | odom:
104 | Value: true
105 | right_wheel:
106 | Value: true
107 | Marker Scale: 1
108 | Name: TF
109 | Show Arrows: true
110 | Show Axes: true
111 | Show Names: true
112 | Tree:
113 | odom:
114 | chassis:
115 | kinect:
116 | {}
117 | kinect_link:
118 | {}
119 | left_wheel:
120 | {}
121 | right_wheel:
122 | {}
123 | Update Interval: 0
124 | Value: true
125 | - Alpha: 1
126 | Autocompute Intensity Bounds: true
127 | Autocompute Value Bounds:
128 | Max Value: 10
129 | Min Value: -10
130 | Value: true
131 | Axis: Z
132 | Channel Name: intensity
133 | Class: rviz/LaserScan
134 | Color: 255; 255; 255
135 | Color Transformer: Intensity
136 | Decay Time: 0
137 | Enabled: true
138 | Invert Rainbow: false
139 | Max Color: 255; 255; 255
140 | Max Intensity: 4096
141 | Min Color: 0; 0; 0
142 | Min Intensity: 0
143 | Name: LaserScan
144 | Position Transformer: XYZ
145 | Queue Size: 10
146 | Selectable: true
147 | Size (Pixels): 3
148 | Size (m): 0.00999999978
149 | Style: Flat Squares
150 | Topic: /kinect/scan
151 | Unreliable: false
152 | Use Fixed Frame: true
153 | Use rainbow: true
154 | Value: true
155 | Enabled: true
156 | Global Options:
157 | Background Color: 48; 48; 48
158 | Default Light: true
159 | Fixed Frame: odom
160 | Frame Rate: 30
161 | Name: root
162 | Tools:
163 | - Class: rviz/Interact
164 | Hide Inactive Objects: true
165 | - Class: rviz/MoveCamera
166 | - Class: rviz/Select
167 | - Class: rviz/FocusCamera
168 | - Class: rviz/Measure
169 | - Class: rviz/SetInitialPose
170 | Topic: /initialpose
171 | - Class: rviz/SetGoal
172 | Topic: /move_base_simple/goal
173 | - Class: rviz/PublishPoint
174 | Single click: true
175 | Topic: /clicked_point
176 | Value: true
177 | Views:
178 | Current:
179 | Class: rviz/Orbit
180 | Distance: 16.2611046
181 | Enable Stereo Rendering:
182 | Stereo Eye Separation: 0.0599999987
183 | Stereo Focal Distance: 1
184 | Swap Stereo Eyes: false
185 | Value: false
186 | Focal Point:
187 | X: -0.28541708
188 | Y: -0.0437853597
189 | Z: -0.0722417384
190 | Focal Shape Fixed Size: true
191 | Focal Shape Size: 0.0500000007
192 | Invert Z Axis: false
193 | Name: Current View
194 | Near Clip Distance: 0.00999999978
195 | Pitch: 0.975397944
196 | Target Frame:
197 | Value: Orbit (rviz)
198 | Yaw: 3.33540511
199 | Saved: ~
200 | Window Geometry:
201 | Displays:
202 | collapsed: false
203 | Height: 1056
204 | Hide Left Dock: false
205 | Hide Right Dock: true
206 | QMainWindow State: 000000ff00000000fd00000004000000000000018d00000388fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006600fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000388000000e200fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d006500720061000000021f000000bf0000000000000000fb0000000c00430061006d00650072006101000002b8000000f80000000000000000000000010000011e00000231fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000231000000be00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073500000046fc0100000002fb0000000800540069006d0065010000000000000735000003cc00fffffffb0000000800540069006d00650100000000000004500000000000000000000005a20000038800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
207 | Selection:
208 | collapsed: false
209 | Time:
210 | collapsed: false
211 | Tool Properties:
212 | collapsed: false
213 | Views:
214 | collapsed: true
215 | Width: 1845
216 | X: 75
217 | Y: 24
218 |
--------------------------------------------------------------------------------
/navros_pkg/rviz/map.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz/Displays
3 | Help Height: 78
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /Global Options1
8 | - /Status1
9 | Splitter Ratio: 0.5
10 | Tree Height: 750
11 | - Class: rviz/Selection
12 | Name: Selection
13 | - Class: rviz/Tool Properties
14 | Expanded:
15 | - /2D Pose Estimate1
16 | - /2D Nav Goal1
17 | - /Publish Point1
18 | Name: Tool Properties
19 | Splitter Ratio: 0.588679016
20 | - Class: rviz/Views
21 | Expanded:
22 | - /Current View1
23 | Name: Views
24 | Splitter Ratio: 0.5
25 | - Class: rviz/Time
26 | Experimental: false
27 | Name: Time
28 | SyncMode: 0
29 | SyncSource: LaserScan
30 | Visualization Manager:
31 | Class: ""
32 | Displays:
33 | - Alpha: 0.5
34 | Cell Size: 1
35 | Class: rviz/Grid
36 | Color: 160; 160; 164
37 | Enabled: true
38 | Line Style:
39 | Line Width: 0.0299999993
40 | Value: Lines
41 | Name: Grid
42 | Normal Cell Count: 0
43 | Offset:
44 | X: 0
45 | Y: 0
46 | Z: 0
47 | Plane: XY
48 | Plane Cell Count: 10
49 | Reference Frame:
50 | Value: true
51 | - Alpha: 1
52 | Class: rviz/RobotModel
53 | Collision Enabled: false
54 | Enabled: true
55 | Links:
56 | All Links Enabled: true
57 | Expand Joint Details: false
58 | Expand Link Details: false
59 | Expand Tree: false
60 | Link Tree Style: Links in Alphabetic Order
61 | chassis:
62 | Alpha: 1
63 | Show Axes: false
64 | Show Trail: false
65 | Value: true
66 | kinect:
67 | Alpha: 1
68 | Show Axes: false
69 | Show Trail: false
70 | Value: true
71 | kinect_link:
72 | Alpha: 1
73 | Show Axes: false
74 | Show Trail: false
75 | left_wheel:
76 | Alpha: 1
77 | Show Axes: false
78 | Show Trail: false
79 | Value: true
80 | right_wheel:
81 | Alpha: 1
82 | Show Axes: false
83 | Show Trail: false
84 | Value: true
85 | Name: RobotModel
86 | Robot Description: robot_description
87 | TF Prefix: ""
88 | Update Interval: 0
89 | Value: true
90 | Visual Enabled: true
91 | - Class: rviz/TF
92 | Enabled: true
93 | Frame Timeout: 15
94 | Frames:
95 | All Enabled: true
96 | chassis:
97 | Value: true
98 | kinect:
99 | Value: true
100 | kinect_link:
101 | Value: true
102 | left_wheel:
103 | Value: true
104 | map:
105 | Value: true
106 | odom:
107 | Value: true
108 | right_wheel:
109 | Value: true
110 | Marker Scale: 1
111 | Name: TF
112 | Show Arrows: true
113 | Show Axes: true
114 | Show Names: true
115 | Tree:
116 | map:
117 | {}
118 | odom:
119 | chassis:
120 | kinect:
121 | {}
122 | kinect_link:
123 | {}
124 | left_wheel:
125 | {}
126 | right_wheel:
127 | {}
128 | Update Interval: 0
129 | Value: true
130 | - Alpha: 1
131 | Autocompute Intensity Bounds: true
132 | Autocompute Value Bounds:
133 | Max Value: 10
134 | Min Value: -10
135 | Value: true
136 | Axis: Z
137 | Channel Name: intensity
138 | Class: rviz/LaserScan
139 | Color: 255; 255; 255
140 | Color Transformer: Intensity
141 | Decay Time: 0
142 | Enabled: true
143 | Invert Rainbow: false
144 | Max Color: 255; 255; 255
145 | Max Intensity: 4096
146 | Min Color: 0; 0; 0
147 | Min Intensity: 0
148 | Name: LaserScan
149 | Position Transformer: XYZ
150 | Queue Size: 10
151 | Selectable: true
152 | Size (Pixels): 3
153 | Size (m): 0.00999999978
154 | Style: Flat Squares
155 | Topic: /kinect/scan
156 | Unreliable: false
157 | Use Fixed Frame: true
158 | Use rainbow: true
159 | Value: true
160 | - Alpha: 0.699999988
161 | Class: rviz/Map
162 | Color Scheme: map
163 | Draw Behind: false
164 | Enabled: true
165 | Name: Map
166 | Topic: /map
167 | Unreliable: false
168 | Use Timestamp: false
169 | Value: true
170 | Enabled: true
171 | Global Options:
172 | Background Color: 48; 48; 48
173 | Default Light: true
174 | Fixed Frame: odom
175 | Frame Rate: 30
176 | Name: root
177 | Tools:
178 | - Class: rviz/Interact
179 | Hide Inactive Objects: true
180 | - Class: rviz/MoveCamera
181 | - Class: rviz/Select
182 | - Class: rviz/FocusCamera
183 | - Class: rviz/Measure
184 | - Class: rviz/SetInitialPose
185 | Topic: /initialpose
186 | - Class: rviz/SetGoal
187 | Topic: /move_base_simple/goal
188 | - Class: rviz/PublishPoint
189 | Single click: true
190 | Topic: /clicked_point
191 | Value: true
192 | Views:
193 | Current:
194 | Class: rviz/Orbit
195 | Distance: 16.2611046
196 | Enable Stereo Rendering:
197 | Stereo Eye Separation: 0.0599999987
198 | Stereo Focal Distance: 1
199 | Swap Stereo Eyes: false
200 | Value: false
201 | Focal Point:
202 | X: -0.28541708
203 | Y: -0.0437853597
204 | Z: -0.0722417384
205 | Focal Shape Fixed Size: true
206 | Focal Shape Size: 0.0500000007
207 | Invert Z Axis: false
208 | Name: Current View
209 | Near Clip Distance: 0.00999999978
210 | Pitch: 0.975397944
211 | Target Frame:
212 | Value: Orbit (rviz)
213 | Yaw: 3.33540511
214 | Saved: ~
215 | Window Geometry:
216 | Displays:
217 | collapsed: false
218 | Height: 1056
219 | Hide Left Dock: false
220 | Hide Right Dock: true
221 | QMainWindow State: 000000ff00000000fd00000004000000000000018d00000388fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006600fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000388000000e200fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d006500720061000000021f000000bf0000000000000000fb0000000c00430061006d00650072006101000002b8000000f80000000000000000000000010000011e00000231fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000231000000be00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073500000046fc0100000002fb0000000800540069006d0065010000000000000735000003cc00fffffffb0000000800540069006d00650100000000000004500000000000000000000005a20000038800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
222 | Selection:
223 | collapsed: false
224 | Time:
225 | collapsed: false
226 | Tool Properties:
227 | collapsed: false
228 | Views:
229 | collapsed: true
230 | Width: 1845
231 | X: 75
232 | Y: 24
233 |
--------------------------------------------------------------------------------
/navros_pkg/rviz/navigate.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz/Displays
3 | Help Height: 78
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /Global Options1
8 | Splitter Ratio: 0.5
9 | Tree Height: 750
10 | - Class: rviz/Selection
11 | Name: Selection
12 | - Class: rviz/Tool Properties
13 | Expanded:
14 | - /2D Pose Estimate1
15 | - /2D Nav Goal1
16 | - /Publish Point1
17 | Name: Tool Properties
18 | Splitter Ratio: 0.588679016
19 | - Class: rviz/Views
20 | Expanded:
21 | - /Current View1
22 | Name: Views
23 | Splitter Ratio: 0.5
24 | - Class: rviz/Time
25 | Experimental: false
26 | Name: Time
27 | SyncMode: 0
28 | SyncSource: LaserScan
29 | Visualization Manager:
30 | Class: ""
31 | Displays:
32 | - Alpha: 0.5
33 | Cell Size: 1
34 | Class: rviz/Grid
35 | Color: 160; 160; 164
36 | Enabled: true
37 | Line Style:
38 | Line Width: 0.0299999993
39 | Value: Lines
40 | Name: Grid
41 | Normal Cell Count: 0
42 | Offset:
43 | X: 0
44 | Y: 0
45 | Z: 0
46 | Plane: XY
47 | Plane Cell Count: 10
48 | Reference Frame:
49 | Value: true
50 | - Alpha: 1
51 | Class: rviz/RobotModel
52 | Collision Enabled: false
53 | Enabled: true
54 | Links:
55 | All Links Enabled: true
56 | Expand Joint Details: false
57 | Expand Link Details: false
58 | Expand Tree: false
59 | Link Tree Style: Links in Alphabetic Order
60 | chassis:
61 | Alpha: 1
62 | Show Axes: false
63 | Show Trail: false
64 | Value: true
65 | kinect:
66 | Alpha: 1
67 | Show Axes: false
68 | Show Trail: false
69 | Value: true
70 | kinect_link:
71 | Alpha: 1
72 | Show Axes: false
73 | Show Trail: false
74 | left_wheel:
75 | Alpha: 1
76 | Show Axes: false
77 | Show Trail: false
78 | Value: true
79 | right_wheel:
80 | Alpha: 1
81 | Show Axes: false
82 | Show Trail: false
83 | Value: true
84 | Name: RobotModel
85 | Robot Description: robot_description
86 | TF Prefix: ""
87 | Update Interval: 0
88 | Value: true
89 | Visual Enabled: true
90 | - Class: rviz/TF
91 | Enabled: true
92 | Frame Timeout: 15
93 | Frames:
94 | All Enabled: true
95 | chassis:
96 | Value: true
97 | kinect:
98 | Value: true
99 | kinect_link:
100 | Value: true
101 | left_wheel:
102 | Value: true
103 | map:
104 | Value: true
105 | odom:
106 | Value: true
107 | right_wheel:
108 | Value: true
109 | Marker Scale: 1
110 | Name: TF
111 | Show Arrows: true
112 | Show Axes: true
113 | Show Names: true
114 | Tree:
115 | map:
116 | odom:
117 | chassis:
118 | kinect:
119 | {}
120 | kinect_link:
121 | {}
122 | left_wheel:
123 | {}
124 | right_wheel:
125 | {}
126 | Update Interval: 0
127 | Value: true
128 | - Alpha: 1
129 | Autocompute Intensity Bounds: true
130 | Autocompute Value Bounds:
131 | Max Value: 10
132 | Min Value: -10
133 | Value: true
134 | Axis: Z
135 | Channel Name: intensity
136 | Class: rviz/LaserScan
137 | Color: 255; 255; 255
138 | Color Transformer: Intensity
139 | Decay Time: 0
140 | Enabled: true
141 | Invert Rainbow: false
142 | Max Color: 255; 255; 255
143 | Max Intensity: 4096
144 | Min Color: 0; 0; 0
145 | Min Intensity: 0
146 | Name: LaserScan
147 | Position Transformer: XYZ
148 | Queue Size: 10
149 | Selectable: true
150 | Size (Pixels): 3
151 | Size (m): 0.00999999978
152 | Style: Flat Squares
153 | Topic: /kinect/scan
154 | Unreliable: false
155 | Use Fixed Frame: true
156 | Use rainbow: true
157 | Value: true
158 | - Alpha: 0.699999988
159 | Class: rviz/Map
160 | Color Scheme: map
161 | Draw Behind: false
162 | Enabled: true
163 | Name: Map
164 | Topic: /map
165 | Unreliable: false
166 | Use Timestamp: false
167 | Value: true
168 | - Alpha: 1
169 | Arrow Length: 0.300000012
170 | Axes Length: 0.300000012
171 | Axes Radius: 0.00999999978
172 | Class: rviz/PoseArray
173 | Color: 255; 25; 0
174 | Enabled: true
175 | Head Length: 0.0700000003
176 | Head Radius: 0.0299999993
177 | Name: PoseArray
178 | Shaft Length: 0.230000004
179 | Shaft Radius: 0.00999999978
180 | Shape: Arrow (Flat)
181 | Topic: /particlecloud
182 | Unreliable: false
183 | Value: true
184 | - Alpha: 1
185 | Buffer Length: 1
186 | Class: rviz/Path
187 | Color: 25; 255; 0
188 | Enabled: true
189 | Head Diameter: 0.300000012
190 | Head Length: 0.200000003
191 | Length: 0.300000012
192 | Line Style: Lines
193 | Line Width: 0.0299999993
194 | Name: Path
195 | Offset:
196 | X: 0
197 | Y: 0
198 | Z: 0
199 | Pose Color: 255; 85; 255
200 | Pose Style: None
201 | Radius: 0.0299999993
202 | Shaft Diameter: 0.100000001
203 | Shaft Length: 0.100000001
204 | Topic: /move_base/NavfnROS/plan
205 | Unreliable: false
206 | Value: true
207 | - Alpha: 0.699999988
208 | Class: rviz/Map
209 | Color Scheme: costmap
210 | Draw Behind: false
211 | Enabled: true
212 | Name: Map
213 | Topic: /move_base/global_costmap/costmap
214 | Unreliable: false
215 | Use Timestamp: false
216 | Value: true
217 | Enabled: true
218 | Global Options:
219 | Background Color: 48; 48; 48
220 | Default Light: true
221 | Fixed Frame: map
222 | Frame Rate: 30
223 | Name: root
224 | Tools:
225 | - Class: rviz/Interact
226 | Hide Inactive Objects: true
227 | - Class: rviz/MoveCamera
228 | - Class: rviz/Select
229 | - Class: rviz/FocusCamera
230 | - Class: rviz/Measure
231 | - Class: rviz/SetInitialPose
232 | Topic: /initialpose
233 | - Class: rviz/SetGoal
234 | Topic: /move_base_simple/goal
235 | - Class: rviz/PublishPoint
236 | Single click: true
237 | Topic: /clicked_point
238 | Value: true
239 | Views:
240 | Current:
241 | Class: rviz/Orbit
242 | Distance: 20.6048012
243 | Enable Stereo Rendering:
244 | Stereo Eye Separation: 0.0599999987
245 | Stereo Focal Distance: 1
246 | Swap Stereo Eyes: false
247 | Value: false
248 | Focal Point:
249 | X: -0.28541708
250 | Y: -0.0437853597
251 | Z: -0.0722417384
252 | Focal Shape Fixed Size: true
253 | Focal Shape Size: 0.0500000007
254 | Invert Z Axis: false
255 | Name: Current View
256 | Near Clip Distance: 0.00999999978
257 | Pitch: 1.39979637
258 | Target Frame:
259 | Value: Orbit (rviz)
260 | Yaw: 3.25540352
261 | Saved: ~
262 | Window Geometry:
263 | Displays:
264 | collapsed: false
265 | Height: 1056
266 | Hide Left Dock: false
267 | Hide Right Dock: true
268 | QMainWindow State: 000000ff00000000fd00000004000000000000018d00000388fc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006600fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000388000000e200fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d006500720061000000021f000000bf0000000000000000fb0000000c00430061006d00650072006101000002b8000000f80000000000000000000000010000011e00000231fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000231000000be00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073500000046fc0100000002fb0000000800540069006d0065010000000000000735000003cc00fffffffb0000000800540069006d00650100000000000004500000000000000000000005a20000038800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
269 | Selection:
270 | collapsed: false
271 | Time:
272 | collapsed: false
273 | Tool Properties:
274 | collapsed: false
275 | Views:
276 | collapsed: true
277 | Width: 1845
278 | X: 75
279 | Y: 24
280 |
--------------------------------------------------------------------------------
/navros_pkg/rviz/octomap.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz/Displays
3 | Help Height: 78
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /Global Options1
8 | - /Status1
9 | - /Map1
10 | - /MarkerArray1
11 | Splitter Ratio: 0.5
12 | Tree Height: 767
13 | - Class: rviz/Selection
14 | Name: Selection
15 | - Class: rviz/Tool Properties
16 | Expanded:
17 | - /2D Pose Estimate1
18 | - /2D Nav Goal1
19 | - /Publish Point1
20 | Name: Tool Properties
21 | Splitter Ratio: 0.588679016
22 | - Class: rviz/Views
23 | Expanded:
24 | - /Current View1
25 | Name: Views
26 | Splitter Ratio: 0.5
27 | - Class: rviz/Time
28 | Experimental: false
29 | Name: Time
30 | SyncMode: 0
31 | SyncSource: LaserScan
32 | Toolbars:
33 | toolButtonStyle: 2
34 | Visualization Manager:
35 | Class: ""
36 | Displays:
37 | - Alpha: 0.5
38 | Cell Size: 1
39 | Class: rviz/Grid
40 | Color: 160; 160; 164
41 | Enabled: true
42 | Line Style:
43 | Line Width: 0.0299999993
44 | Value: Lines
45 | Name: Grid
46 | Normal Cell Count: 0
47 | Offset:
48 | X: 0
49 | Y: 0
50 | Z: 0
51 | Plane: XY
52 | Plane Cell Count: 10
53 | Reference Frame:
54 | Value: true
55 | - Alpha: 1
56 | Class: rviz/RobotModel
57 | Collision Enabled: false
58 | Enabled: true
59 | Links:
60 | All Links Enabled: true
61 | Expand Joint Details: false
62 | Expand Link Details: false
63 | Expand Tree: false
64 | Link Tree Style: Links in Alphabetic Order
65 | chassis:
66 | Alpha: 1
67 | Show Axes: false
68 | Show Trail: false
69 | Value: true
70 | kinect:
71 | Alpha: 1
72 | Show Axes: false
73 | Show Trail: false
74 | Value: true
75 | kinect_link:
76 | Alpha: 1
77 | Show Axes: false
78 | Show Trail: false
79 | left_wheel:
80 | Alpha: 1
81 | Show Axes: false
82 | Show Trail: false
83 | Value: true
84 | right_wheel:
85 | Alpha: 1
86 | Show Axes: false
87 | Show Trail: false
88 | Value: true
89 | Name: RobotModel
90 | Robot Description: robot_description
91 | TF Prefix: ""
92 | Update Interval: 0
93 | Value: true
94 | Visual Enabled: true
95 | - Class: rviz/TF
96 | Enabled: true
97 | Frame Timeout: 15
98 | Frames:
99 | All Enabled: true
100 | chassis:
101 | Value: true
102 | kinect:
103 | Value: true
104 | kinect_link:
105 | Value: true
106 | left_wheel:
107 | Value: true
108 | map:
109 | Value: true
110 | odom:
111 | Value: true
112 | right_wheel:
113 | Value: true
114 | Marker Scale: 1
115 | Name: TF
116 | Show Arrows: true
117 | Show Axes: true
118 | Show Names: true
119 | Tree:
120 | map:
121 | odom:
122 | chassis:
123 | kinect:
124 | {}
125 | kinect_link:
126 | {}
127 | left_wheel:
128 | {}
129 | right_wheel:
130 | {}
131 | Update Interval: 0
132 | Value: true
133 | - Alpha: 1
134 | Autocompute Intensity Bounds: true
135 | Autocompute Value Bounds:
136 | Max Value: 10
137 | Min Value: -10
138 | Value: true
139 | Axis: Z
140 | Channel Name: intensity
141 | Class: rviz/LaserScan
142 | Color: 255; 255; 255
143 | Color Transformer: Intensity
144 | Decay Time: 0
145 | Enabled: true
146 | Invert Rainbow: false
147 | Max Color: 255; 255; 255
148 | Max Intensity: 4096
149 | Min Color: 0; 0; 0
150 | Min Intensity: 0
151 | Name: LaserScan
152 | Position Transformer: XYZ
153 | Queue Size: 10
154 | Selectable: true
155 | Size (Pixels): 3
156 | Size (m): 0.00999999978
157 | Style: Flat Squares
158 | Topic: /kinect/scan
159 | Unreliable: false
160 | Use Fixed Frame: true
161 | Use rainbow: true
162 | Value: true
163 | - Alpha: 0.699999988
164 | Class: rviz/Map
165 | Color Scheme: map
166 | Draw Behind: false
167 | Enabled: true
168 | Name: Map
169 | Topic: /projected_map
170 | Unreliable: false
171 | Use Timestamp: false
172 | Value: true
173 | - Class: rviz/MarkerArray
174 | Enabled: true
175 | Marker Topic: /occupied_cells_vis_array
176 | Name: MarkerArray
177 | Namespaces:
178 | map: true
179 | Queue Size: 100
180 | Value: true
181 | Enabled: true
182 | Global Options:
183 | Background Color: 48; 48; 48
184 | Default Light: true
185 | Fixed Frame: map
186 | Frame Rate: 30
187 | Name: root
188 | Tools:
189 | - Class: rviz/Interact
190 | Hide Inactive Objects: true
191 | - Class: rviz/MoveCamera
192 | - Class: rviz/Select
193 | - Class: rviz/FocusCamera
194 | - Class: rviz/Measure
195 | - Class: rviz/SetInitialPose
196 | Topic: /initialpose
197 | - Class: rviz/SetGoal
198 | Topic: /move_base_simple/goal
199 | - Class: rviz/PublishPoint
200 | Single click: true
201 | Topic: /clicked_point
202 | Value: true
203 | Views:
204 | Current:
205 | Class: rviz/Orbit
206 | Distance: 5.84805441
207 | Enable Stereo Rendering:
208 | Stereo Eye Separation: 0.0599999987
209 | Stereo Focal Distance: 1
210 | Swap Stereo Eyes: false
211 | Value: false
212 | Focal Point:
213 | X: -0.418741435
214 | Y: 0.868555605
215 | Z: 0.7522946
216 | Focal Shape Fixed Size: true
217 | Focal Shape Size: 0.0500000007
218 | Invert Z Axis: false
219 | Name: Current View
220 | Near Clip Distance: 0.00999999978
221 | Pitch: 0.709797204
222 | Target Frame:
223 | Value: Orbit (rviz)
224 | Yaw: 3.13540101
225 | Saved: ~
226 | Window Geometry:
227 | Displays:
228 | collapsed: false
229 | Height: 1056
230 | Hide Left Dock: false
231 | Hide Right Dock: true
232 | QMainWindow State: 000000ff00000000fd00000004000000000000018d0000038efc020000000afb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000038e000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d006500720061000000021f000000bf0000000000000000fb0000000c00430061006d00650072006101000002b8000000f80000000000000000000000010000011e00000231fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000231000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f00000046fc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000005ac0000038e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
233 | Selection:
234 | collapsed: false
235 | Time:
236 | collapsed: false
237 | Tool Properties:
238 | collapsed: false
239 | Views:
240 | collapsed: true
241 | Width: 1855
242 | X: 65
243 | Y: 24
244 |
--------------------------------------------------------------------------------
/navros_pkg/screenshots/grid_slam.jpg:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/morou34/Navigation-of-an-Autonomous-Differential-Drive-Robot/949e3d187e54dd3ab9ba951b77cecd9f45a44412/navros_pkg/screenshots/grid_slam.jpg
--------------------------------------------------------------------------------
/navros_pkg/screenshots/grid_slam.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/morou34/Navigation-of-an-Autonomous-Differential-Drive-Robot/949e3d187e54dd3ab9ba951b77cecd9f45a44412/navros_pkg/screenshots/grid_slam.png
--------------------------------------------------------------------------------
/navros_pkg/screenshots/navigation.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/morou34/Navigation-of-an-Autonomous-Differential-Drive-Robot/949e3d187e54dd3ab9ba951b77cecd9f45a44412/navros_pkg/screenshots/navigation.png
--------------------------------------------------------------------------------
/navros_pkg/screenshots/small_house.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/morou34/Navigation-of-an-Autonomous-Differential-Drive-Robot/949e3d187e54dd3ab9ba951b77cecd9f45a44412/navros_pkg/screenshots/small_house.png
--------------------------------------------------------------------------------
/navros_pkg/urdf/car.urdf.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 | 0
64 | 0
65 | 1.0
66 | 1.0
67 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 |
85 |
86 |
87 |
88 |
89 |
90 |
91 |
92 |
93 |
94 |
95 |
96 |
97 |
98 |
99 |
100 |
101 |
102 |
103 |
104 |
105 |
106 |
107 |
108 |
109 |
110 |
111 |
112 |
113 |
114 |
115 |
116 |
117 |
118 |
119 |
120 |
121 |
122 |
123 |
124 |
125 |
126 |
127 |
128 |
129 |
130 |
131 |
132 |
133 |
134 |
135 |
136 |
137 |
138 |
139 |
140 |
141 |
142 |
143 |
144 |
145 |
146 |
147 |
148 |
149 |
150 |
151 |
152 |
153 |
154 |
155 |
156 |
157 |
158 |
159 |
160 |
161 |
162 |
163 |
164 |
165 |
166 |
167 |
168 |
169 |
170 |
171 |
172 |
173 |
174 |
175 |
176 |
177 |
178 |
179 |
180 |
181 |
182 |
183 |
184 |
185 |
186 |
187 |
188 |
189 |
190 |
191 |
192 |
193 |
194 |
--------------------------------------------------------------------------------
/navros_pkg/urdf/gazebo_plugins.urdf.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 | Gazebo/Grey
7 |
8 |
9 |
10 | Gazebo/Blue
11 |
12 |
13 |
14 | Gazebo/Yellow
15 |
16 |
17 |
18 | Gazebo/Yellow
19 |
20 |
21 |
22 | Gazebo/Black
23 |
24 |
25 |
26 |
27 |
28 | false
29 | true
30 | 20
31 | joint_left_wheel_chassis
32 | joint_right_wheel_chassis
33 | True
34 | 0.2
35 | 0.2
36 | 0.1
37 | cmd_vel
38 | odom
39 | odom
40 | chassis
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 | 1
49 | true
50 |
51 | 1.047
52 |
53 | 640
54 | 480
55 | R8G8B8
56 |
57 |
58 |
59 |
60 |
61 | 0.1
62 | 100
63 |
64 |
65 |
66 | true
67 | 10.0
68 | kinect
69 | kinect_link
70 | rgb/image_raw
71 | depth/image_raw
72 | depth/points
73 | rgb/camera_info
74 | depth/camera_info
75 | 0.4
76 | 0.07
77 | 0.0
78 | 0.0
79 | 0.0
80 | 0.0
81 | 0.0
82 | 0.0
83 | 0.0
84 | 0.0
85 | 0.0
86 |
87 |
88 |
89 |
90 |
91 |
--------------------------------------------------------------------------------