Skip to content

Commit

Permalink
Merge pull request #2 from RajPShinde/navigation_devel
Browse files Browse the repository at this point in the history
Autonomous Navigation
  • Loading branch information
shubham1925 authored Nov 18, 2020
2 parents e6b34a8 + 8fa795f commit 00f8dea
Show file tree
Hide file tree
Showing 255 changed files with 17,022 additions and 86 deletions.
2 changes: 1 addition & 1 deletion .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ language: generic
# Configuration variables. All variables are global
env:
global:
- ROS_DISTRO=melodic
- ROS_DISTRO=kinetic
- ROS_CI_DESKTOP="`lsb_release -cs`" # e.g. [precise|trusty|...]
- CI_SOURCE_PATH=$(pwd)
- ROSINSTALL_FILE=$CI_SOURCE_PATH/dependencies.rosinstall
Expand Down
61 changes: 57 additions & 4 deletions CMakeLists.txt
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})
56 changes: 41 additions & 15 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,33 +3,34 @@
[![Build Status](https://travis-ci.org/RajPShinde/Autonomous_Wheelchair.svg?branch=master)](https://travis-ci.org/RajPShinde/Autonomous_Wheelchair)
[![Coverage Status](https://coveralls.io/repos/github/RajPShinde/Autonomous_Wheelchair/badge.svg?branch=master&service=github)](https://coveralls.io/github/RajPShinde/Autonomous_Wheelchair?branch=master&service=github)
[![License BSD 3-Clause](https://img.shields.io/badge/License-BSD%203--Clause-blue.svg)](https://github.com/RajPShinde/Autonomous_Wheelchair/blob/master/LICENSE)
[![Documentation](https://img.shields.io/badge/docs-unknown-lightgrey)](https://github.com/RajPShinde/Autonomous_Wheelchair/docs)
[![Documentation](https://img.shields.io/badge/docs-generated-brightgreen.svg)](https://github.com/RajPShinde/Autonomous_Wheelchair/doxygen)
---

## Authors

* **Raj Prakash Shinde** [GitHub](https://github.com/RajPShinde)
<br>I am a Masters in Robotics Engineering student at the University of Maryland, College Park. My primary area of interest are Legged Robotics and Automation.
* **Shubham Sonawane** [GitHub](https://github.com/shubham1925)
<br>I am a Master's in Robotics Engineering student at the University of Maryland, College Park.
* **Prasheel Renkuntla** [GitHub](https://github.com/Prasheel24)
<br>I am a Master's in Robotics Engineering student at the University of Maryland, College Park. My primary area of interest is in Vision integrated Robot Systems.

## Overview
A ROS Stack to make a Wheelchair Navigate Wheelchair Autonomously in an indoor Environment.
* **Raj Prakash Shinde** [Porfolio](https://rajpshinde.github.io/)
* **Shubham Sonawane** [Porfolio](https://shubhamsonawane.wixsite.com/portfolio)
* **Prasheel Renkuntla** [Porfolio](https://prasheel24.github.io/)

## Description
A ROS Package to make a Differential-Drive Wheelchair Navigate Autonomously in an indoor Environment using onboard LiDAR and Sonar Sensors. The Wheelchair provides manual control to user through a joystick, in case the wheelchair deviates from its path.
<p align="center">
<img src="data/simulation.gif"/>
</p>
<p align="center">
<img src="data/wheelchair.gif"/>
</p>

## Dependencies
1. Ubuntu 16.04 or >
2. ROS Kinetic or >
3. Navigation Stack

## Sprint Planning and Discussion
Sprint Discussion's - [Link](https://docs.google.com/document/d/1YxuiONLKsmspN5a6GJSREl9pPx3vZLULn2Mh-LnGHLA/edit?usp=sharing)

## Agile Iterative Process Log
Access Product Backlog, Worklog & Iteration Log here- [Link](https://docs.google.com/spreadsheets/d/16jTj_WTD0Le5l6ijkAiI3PhKVDuv9GQzufeO_Imgy9o/edit?usp=sharing)

## Dependencies
1. Ubuntu 16.04
2. C++ 11/14/17

## Build
Steps to build
```
Expand All @@ -42,6 +43,31 @@ git clone https://github.com/RajPShinde/Autonomous_Wheelchair
cd ~/catkin_ws/
catkin_make
```
To build tests
```
catkin_make tests
```
## Run
Mapping
```
source devel/setup.bash
roslaunch autonomous_wheelchair simulationMapping.launch
```
Navigation
```
source devel/setup.bash
roslaunch autonomous_wheelchair simulationNavigation.launch
```
Tests
```
source devel/setup.bash
catkin_make run_tests
```
## TODO
REplace with TEB Motion Planner

## Bugs
None

## Disclaimer
```
Expand Down
5 changes: 5 additions & 0 deletions config/astar_plugin.xml
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>
17 changes: 17 additions & 0 deletions config/base_local_planner_params.yaml
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
9 changes: 9 additions & 0 deletions config/costmap_common_params.yaml
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}
9 changes: 9 additions & 0 deletions config/global_costmap_params.yaml
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
19 changes: 19 additions & 0 deletions config/global_planner_params.yaml
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
10 changes: 10 additions & 0 deletions config/local_costmap_params.yaml
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
9 changes: 9 additions & 0 deletions config/move_base_params.yaml
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.
Loading

0 comments on commit 00f8dea

Please sign in to comment.