• Stars
    star
    183
  • Rank 210,154 (Top 5 %)
  • Language
    C++
  • Created almost 5 years ago
  • Updated over 1 year ago

Reviews

There are no reviews yet. Be the first to send feedback to the community and the maintainers!

Repository Details

GPS points will be predefined in ROS based robots to navigate to the destination avoiding obstacles.

GPS-waypoint-based-Autonomous-Navigation-in-ROS

GPS points will be predefined for the robot to navigate to the destination avoiding obstacles.

This repo package was tested on:

Custom Rover has

  • Nvidia Jetson TX2 with Ubuntu 18.04
  • Razor 9DOF IMU,
  • ZED F9P (RTK2) GPS, and
  • RPLidar A1 lidar.

The base station has

  • Laptop with Ubuntu 18.04

Motivation

This work was performed to participate in University Rover Challenge (URC) 2019 for Team Interplanetar (BUET Mars Rover Robotics Team). Special thanks goes to Daniel Snider for open sourcing his work:

Run the package

In your terminal, navigate to your catkin_ws's source (src) directory & run:

cd catkin_ws/src
git clone https://github.com/ArghyaChatterjee/gps-waypoint-based-autonomous-navigation-in-ros.git gps_waypoint_nav
cd ..
catkin_make --only-pkg-with-deps gps_waypoint_nav

In that terminal, launch the navigation file:

source devel/setup.bash
roslaunch gps_waypoint_nav gps_waypoint_nav.launch

In another terminal, launch the joystick controller file:

source devel/setup.bash
roslaunch gps_waypoint_nav joy_launch_control.launch

Run the rover with the joystick. During the run, press "LB" to start collecting waypoints. The waypoints will be saved inside 'points_outdoor.txt'. When the run is finished, press "RB" to start following waypoints.

Package Description

This package uses a combination of the following packages:

  • ekf_localization to fuse odometry data with IMU and GPS data.
  • navsat_transform to convert GPS data to odometry and to convert latitude and longitude points to the robot's odometry coordinate system.
  • GMapping to create a map and detect obstacles.
  • move_base to navigate to the goals while avoiding obstacles
  • goals are set using recorded or inputted waypoints.

Node Description

The Navigation package within this repo includes the following custom nodes:

  • gps_waypoint to read the waypoint file, convert waypoints to points in the map frame and then send the goals to move_base.
  • gps_waypoint_continuous1 for continuous navigation between waypoints using one controller.
  • gps_waypoint_continuous2 for continuous navigation between waypoints using another seperate controller.
  • collect_gps_waypoint to allow the user to drive the robot around and collect their own waypoints.
  • calibrate_heading to set the heading of the robot at startup and fix issues with poor magnetometer data.
  • plot_gps_waypoints to save raw data from the GPS for plotting purposes.
  • gps_waypoint_mapping to combine waypoint navigation with Mandala Robotics' 3D mapping software for 3D mapping.

Convert lattitude-longitude to local odometry message

If you want to convert /navsat/fix topic from gps sensor to /navsat/odom topic (local cordinate frame), use these 2 packages directly:

Details Understanding of the package

GPS related ros drivers

Related Issues

Related Implementation to ROS robot

  • Robot Localization using GPS <website>

User Interface Demo

Mapviz package

We have used mapviz package to visualize the path and the cordinates.

Binary Install:

sudo apt-get install ros-melodic-mapviz \
                       ros-melodic-mapviz-plugins \
                       ros-melodic-tile-map \
                       ros-melodic-multires-image		       

Source Install:

cd catkin_ws/src
git clone https://github.com/swri-robotics/mapviz.git
rosdep install --from-paths src --ignore-src
catkin_make

Delete any previous configuration file that you have worked with. The sequence of plugins in your panel is vital as Mapviz draws its plugins in the order that they are listed in the plugin panel. If navsat is listed first, it will draw that first, and then it will draw the tile_map over that, so you would not be able to see any fixes.

sudo rm ~/.mapviz_config

In one terminal run:

roscore

In another terminal, launch the mapviz file. Your mapviz.launch file should look like this:

<launch>

  <node pkg="mapviz" type="mapviz" name="mapviz"></node>

  <node pkg="swri_transform_util" type="initialize_origin.py" name="initialize_origin" >
    <param name="local_xy_frame" value="/map"/>
    <param name="local_xy_origin" value="auto"/>
    <!--<param name="local_xy_origin" value="swri"/>-->
    <rosparam param="local_xy_origins">
      [{ name: swri,
         latitude: 29.45196669,
         longitude: -98.61370577,
         altitude: 233.719,
         heading: 0.0},

       { name: back_40,
         latitude: 29.447507,
         longitude: -98.629367,
         altitude: 200.0,
         heading: 0.0}]
    </rosparam>
    <remap from="fix" to="/navsat/fix"/>
  </node>

  <node pkg="tf" type="static_transform_publisher" name="swri_transform" args="0 0 0 0 0 0 /map /origin 100"  />

</launch>

Use the following command to launch the mapviz.launch file:

cd catkin_ws
source devel/setup.bash
roslaunch mapviz mapviz.launch

In the panel, leave the 1st box (fixed frame "Map" and target frame "None") as it is, add tile_map and then add navsat plugin (select topic /navsat/fix). Perform it sequencially.

Mapviz Testing:

Now, you need a sample bag file which will publish the gps in /navsat/fix topic. Download the rosbag from here. Run the rosbag in another terminal:

rosbag play CA-20190828184706_blur_align.bag

Rviz Satellite Package

Source Install:

cd catkin_ws/src
git clone https://github.com/nobleo/rviz_satellite.git
catkin_make

Use the following command to launch the rviz.launch file:

cd catkin_ws
source devel/setup.bash
roslaunch rviz_satellite demo.launch

Rviz Satellite Testing:

You need a sample bag file which will publish the gps in /navsat/fix topic. Download the rosbag from here. Run the rosbag in another terminal:

rosbag play CA-20190828184706_blur_align.bag

Rosboard Package

Install

Source Install:

cd catkin_ws/src
git clone https://github.com/dheera/rosboard.git
catkin_make

Use the following command to launch the rviz.launch file:

cd catkin_ws
source devel/setup.bash
rosrun rosboard rosboard_node

Rosbaord Testing:

You need a sample bag file which will publish the gps in /navsat/fix topic. Download the rosbag from here. Run the rosbag in another terminal:

rosbag play CA-20190828184706_blur_align.bag

Go to http://localhost:8888 (in case in a robot http://your-robot-ip:8888/) on your local browser and add the topic you want to visualize from top left menu. You should be able to visualize the topics.

Gratitude

I would like to acknowledge the contribution of the websites which helped me while making this repo.

More Repositories

1

waypoint-based-3D-navigation-in-ros

3D waypoints will be predefined in ROS based robots to navigate to the destination avoiding obstacles.
C++
10
star
2

Microsoft-Kinect-v2-SDK-Installation-ROS-Wrapper-and-Rtabmap-on-Ubuntu-18.04

Microsoft Kinect Xbox one is a 3D camera which is widely used for robotics application. In this work, it is demonstrated how to wrap it up with ROS Melodic in Ubuntu 18.04.
C++
7
star
3

object_detection_and_location_tracking_with_zed_camera

It's a repository to use ZED camera with with ZED SDK & ZED Python API for Object detection with Tensorflow.
Python
6
star
4

autonomous-docking-for-mobile-robot-in-ros

autodock is a state machine based auto docking solution for differential-drive robot, allows accurate and reliable docking. It utilizes 3 fiducial markers to locate the position of the docking station. Hence, the Robot should equip with a camera input for fiducial marker detection.
Python
6
star
5

Rover-less-Hector-SLAM-in-ROS-using-Nvidia-Jetson-or-Raspberry-pi

It's a Simultanous Localization And Mapping Technique in ROS which doesnot need any odometry data for realtime simulation in Raspberry pi 3b, 3b+ & Nvidia Jetson Nano
C++
6
star
6

waypoint-based-2D-navigation-in-ros

A number of 2D waypoints will be predefined in ROS based robots to navigate to the destination avoiding obstacles.
Python
5
star
7

april-tag-landmark-based-autonomous-navigation-in-ros

Predefined Landmarks (vertical or horizontal aruco markers) will be treated as points for ROS based robots to navigate to the destination avoiding obstacles.
Python
4
star
8

object_detection_and_location_tracking_in_ros

This repository contains code for object detection and location tracking in ROS with realsense d435 camera.
C
3
star
9

octocopter-for-fire-and-flood-management

It's a Pixhawk & Raspberry Pi based remote controlled or autonomous 8-armed UAV which will fight as firefighter & work as flood relief distributor.
Python
3
star
10

Hardaware-Platforms-for-VIN-and-LOAM

2
star
11

Camera-Calibration-in-ROS

This repository contains tutorial for camera calibration in ROS
2
star
12

SubT-Object-Detection-and-Localization

It's a repository which preserves Artifact detection model in order to detect object using YOLO v3 inside SubT simulator / real world SubT World.
C++
2
star
13

unet-nuclear-thermal-ir-image-segmentation

We evaluated qualitative & quantitative performance of image processing and CNN based automatic methods with manually segmented results on Pool Boiling IR images produced inside MIT’s Nuclear Reactor Laboratory by measuring important boiling heat transfer parameters statistically for each scheme.
Jupyter Notebook
2
star
14

ros-storm32-gimbal

πŸ“Έ STorM32 gimbal controller ROS driver
Python
1
star
15

Velodyne-VLP-lidar-setup-in-ROS

This repository is for velodyne lidar setup with ROS.
1
star
16

Review-Papers-in-SLAM

It's a personal repository to keep track of review research papers in SLAM
1
star
17

ArghyaChatterjee.github.io

https://arghyachatterjee.github.io
HTML
1
star
18

curiosity_mars_rover_description

This repository contains the curiosity mars rover simulation in ROS & gazebo.
Python
1
star
19

URC-Tennis-Ball-Detection

This repository contains ball detection classifier using darknet YOLO v3 model for URC 2019 competition.
Python
1
star