-
Notifications
You must be signed in to change notification settings - Fork 5
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #2 from RajPShinde/navigation_devel
Autonomous Navigation
- Loading branch information
Showing
255 changed files
with
17,022 additions
and
86 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,14 +1,67 @@ | ||
cmake_minimum_required(VERSION 2.8.3) | ||
|
||
cmake_minimum_required(VERSION 3.2.1) | ||
project(autonomous_wheelchair) | ||
|
||
find_package(catkin REQUIRED) | ||
set(CMAKE_EXPORT_COMPILE_COMMANDS ON) | ||
set(CMAKE_CXX_STANDARD 14) | ||
|
||
find_package(catkin REQUIRED COMPONENTS | ||
nav_core | ||
move_base_msgs | ||
base_local_planner | ||
roscpp | ||
std_msgs | ||
tf | ||
rostest | ||
roscpp | ||
rospy | ||
message_generation) | ||
|
||
catkin_package() | ||
catkin_package( | ||
INCLUDE_DIRS include | ||
CATKIN_DEPENDS nav_core roscpp std_msgs | ||
) | ||
|
||
find_package(roslaunch) | ||
|
||
foreach(dir config launch meshes urdf) | ||
install(DIRECTORY ${dir}/ | ||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir}) | ||
endforeach(dir) | ||
|
||
|
||
########### | ||
## Test ## | ||
########### | ||
|
||
if(CATKIN_ENABLE_TESTING) | ||
find_package(rostest REQUIRED) | ||
##find_package(gtest) | ||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -g -O0 --coverage") | ||
|
||
catkin_add_gtest(testGrid test/testGridSquare.cpp src/gridSquare.cpp) | ||
target_link_libraries(testGrid ${catkin_LIBRARIES}) | ||
add_dependencies(testGrid ${catkin_EXPORTED_TARGETS}) | ||
|
||
add_rostest_gtest(testPlanner launch/test/testPathPlanner.launch test/main.cpp test/testPathPlanner.cpp src/gridSquare.cpp src/pathPlanner.cpp) | ||
target_link_libraries(testPlanner ${catkin_LIBRARIES}) | ||
add_dependencies(testPlanner pathPlanner ${catkin_EXPORTED_TARGETS}) | ||
|
||
add_rostest_gtest(testNavigator launch/test/testNavigator.launch test/testNavigateRobot.cpp src/navigateRobot.cpp) | ||
target_link_libraries(testNavigator ${catkin_LIBRARIES}) | ||
add_dependencies(testNavigator navigate ${catkin_EXPORTED_TARGETS}) | ||
endif() | ||
|
||
########### | ||
## Build ## | ||
########### | ||
|
||
include_directories(include ${catkin_INCLUDE_DIRS}) | ||
|
||
add_library(pathPlanner src/gridSquare.cpp src/pathPlanner.cpp) | ||
target_link_libraries(pathPlanner ${catkin_LIBRARIES}) | ||
|
||
add_executable(goal src/goal.cpp) | ||
target_link_libraries(goal ${catkin_LIBRARIES}) | ||
|
||
add_executable(navigate src/main.cpp src/navigateRobot.cpp) | ||
target_link_libraries(navigate ${catkin_LIBRARIES}) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,5 @@ | ||
<library path="lib/libpathPlanner"> | ||
<class name="astar_plugin/AStarPlanner" type="astar_plugin::AStarPlanner" base_class_type="nav_core::BaseGlobalPlanner"> | ||
<description>A* global planner plugin</description> | ||
</class> | ||
</library> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,17 @@ | ||
TrajectoryPlannerROS: | ||
max_vel_x: 0.5 | ||
min_vel_x: 0.1 | ||
max_vel_theta: 2 | ||
min_in_place_vel_theta: 1.2 | ||
acc_lim_theta: 3 | ||
acc_lim_x: 0.75 | ||
acc_lim_y: 0.75 | ||
meter_scoring: true | ||
holonomic_robot: false | ||
recovery_behavior_enabled: true | ||
path_distance_scale: 1.0 | ||
goal_distance_scale: 2.0 | ||
yaw_goal_tolerance: 5.0 | ||
xy_goal_tolerance: 0.7 | ||
occdist_scale: 1.0 | ||
clearing_rotation_allowed: false |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,9 @@ | ||
map_type: costmap | ||
obstacle_range: 2.0 | ||
raytrace_range: 2.0 | ||
footprint: [[0.95, -0.32],[0.95, 0.32], [-0.1, 0.32], [-0.1, -0.32]] | ||
transform_tolerance: 1 | ||
inflation_radius: 1.0 | ||
cost_scaling_factor: 5.0 | ||
observation_sources: laser_scan_sensor | ||
laser_scan_sensor: {sensor_frame: base_laser, data_type: LaserScan, topic: /scan, marking: true, clearing: true} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,9 @@ | ||
global_costmap: | ||
global_frame: map | ||
robot_base_frame: base_link | ||
update_frequency: 5.0 | ||
static_map: true | ||
rolling_window: false | ||
width: 400 | ||
height: 400 | ||
resolution: 0.05 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,19 @@ | ||
GlobalPlanner: # Also see: http://wiki.ros.org/global_planner | ||
old_navfn_behavior: false # Exactly mirror behavior of navfn, use defaults for other boolean parameters, default false | ||
use_quadratic: true # Use the quadratic approximation of the potential. Otherwise, use a simpler calculation, default true | ||
use_dijkstra: false # Use dijkstra's algorithm. Otherwise, A*, default true | ||
use_grid_path: false # Create a path that follows the grid boundaries. Otherwise, use a gradient descent method, default false | ||
|
||
allow_unknown: true # Allow planner to plan through unknown space, default true | ||
#Needs to have track_unknown_space: true in the obstacle / voxel layer (in costmap_commons_param) to work | ||
planner_window_x: 0.0 # default 0.0 | ||
planner_window_y: 0.0 # default 0.0 | ||
default_tolerance: 0.0 # If goal in obstacle, plan to the closest point in radius default_tolerance, default 0.0 | ||
|
||
publish_scale: 100 # Scale by which the published potential gets multiplied, default 100 | ||
planner_costmap_publish_frequency: 0.0 # default 0.0 | ||
|
||
lethal_cost: 253 # default 253 | ||
neutral_cost: 50 # default 50 | ||
cost_factor: 3.0 # Factor to multiply each cost from costmap by, default 3.0 | ||
publish_potential: true # Publish Potential Costmap (this is not like the navfn pointcloud2 potential), default true |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,10 @@ | ||
local_costmap: | ||
global_frame: odom | ||
robot_base_frame: base_link | ||
update_frequency: 5.0 | ||
publish_frequency: 2.0 | ||
static_map: false | ||
rolling_window: true | ||
width: 5 | ||
height: 5 | ||
resolution: 0.05 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,9 @@ | ||
shutdown_costmaps: false | ||
controller_frequency: 5.0 | ||
controller_patience: 3.0 | ||
planner_frequency: 1.0 | ||
planner_patience: 5.0 | ||
oscillation_timeout: 30.0 | ||
oscillation_distance: 0.5 | ||
base_local_planner: "dwa_local_planner/DWAPlannerROS" | ||
base_global_planner: "astar_plugin/AStarPlanner" |
File renamed without changes.
Oops, something went wrong.