Giter Site home page Giter Site logo

maxibooksiyi / astar_turtlebot_ros_gazebo Goto Github PK

View Code? Open in Web Editor NEW

This project forked from pradeep-gopal/astar_turtlebot_ros_gazebo

0.0 0.0 0.0 27.23 MB

Implementation of A star path planning algorithm in python and Simulated it on a Turtlebot 2 robot using ROS Gazebo

Home Page: https://pradeepgopal.site/

CMake 22.61% C 0.84% C++ 5.18% Makefile 47.41% Python 13.46% Shell 0.93% Common Lisp 6.85% JavaScript 2.73%

astar_turtlebot_ros_gazebo's Introduction

Astar_algorithm

Implementation of Astar algorithm and simulation using ROS-Gazebo.

Authors

  1. Sri Manika Makam
  2. Pradeep Gopal

Dependencies

  1. Ubuntu 16.04
  2. ROS kinetic
  3. Gazebo
  4. catkin
  5. Turtlebot3 packages

Libraries:

  1. math
  2. numpy
  3. time
  4. matplotlib
  5. Queue
  6. argparse
  7. rospy
  8. geometry_msgs
  9. std_msgs.msg

Setup

Install turtlebot3-gazebo package by running the below command:

$ sudo apt install ros-kinetic-turtlebot3-gazebo

In your .bashrc file, include the following statements and source it.

source /opt/ros/kinetic/setup.bash
source ~/catkin_ws/devel/setup.bash
export TURTLEBOT3_MODEL=burger

Run the following commands:

$ cd ~/catkin_ws/
$ catkin_make

Instructions to run

The inputs from user are coordinates of start point, orientation of start point (in degrees), coordinates of goal point, two RPM values and clearance.

Robot radius is taken by default as 0.08 (which is half the distance between wheels of the robot). Theta (the angle between the action at each node) is taken as 15. The orientation of goal point is taken by default as 0.

The total clearance is clearance given by user + 0.1 (minimum clearance). Wheel radius is 33mm and distance between the wheels is 160mm for turtlebot3.

Run roscore in one terminal. And in other terminal run the following command:

roslaunch astar_search test.launch x_pos:=4.5 y_pos:=4.5 yaw:=3.14

The start coordinates and goal coordinates should be given as negative of the coordinates as observed in right-handed system because the map given has negative axes. For example, if the robot start point is bottom left (-4.5,-4.5) in right-handed coordinate system, it should be given as (4.5,4.5).

The x,y coordinates of start point should be given in arguments 'x_pos' and 'y_pos' respectively. And argument 'yaw' is (3.14 + orientation at start point in radians). This ensures the turtlebot to spawn at correct position and orientation in gazebo.

Demo

For video 1 (Phase4_video1.mp4):

start point = (4.5,3,0); goal point = (0.5,3,0); clearance = 0; RPM values = (2,3)

The command to run is:

roslaunch astar_search test.launch x_pos:=4.5 y_pos:=3.0 yaw:=3.14

For video 2 (Phase4_video2.mp4):

start point = (4.5,4.5,0); goal point = (-3.5,-3.5,0); clearance = 0.3; RPM values = (2,3)

The command to run is:

roslaunch astar_search test.launch x_pos:=4.5 y_pos:=4.5 yaw:=3.14

astar_turtlebot_ros_gazebo's People

Contributors

pradeep-gopal avatar

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    ๐Ÿ–– Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. ๐Ÿ“Š๐Ÿ“ˆ๐ŸŽ‰

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google โค๏ธ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.