Skip to main content

NexDroid and ROS Integration

Video

We have created a video tutorial on how to connect NexDroid system to ROS.

NexDroid and ROS Integration - Connection and Usage

ROS operating environment initialization

Install Ubuntu 18.04 system, with the image located in "02 Controller/Documents/Setting up Development Environment on a New Computer".

Installation of ROS

This section includes the complete installation steps and ways to troubleshoot errors.

Set up sources.list

Set up your computer to install software from packages.ros.org

sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main"
> /etc/apt/sources.list.d/ros-latest.list'

If the download speed is slow, you can configure the Tsinghua mirror as follows:

sudo sh -c '. /etc/lsb-release && echo "deb http://mirrors.tuna.tsinghua.edu.cn/ros/ubuntu/ `lsb_release -cs` main" >
/etc/apt/sources.list.d/ros-latest.list'

PS: If the download fails, you can try configuring the Aliyun mirror or Tsinghua mirror for Ubuntu. Below is a configuration scheme for the Aliyun mirror.

Backup the source list

The default sources for Ubuntu are not on domestic servers, which can lead to slow software downloads. First, back up the source list file sources.list

sudo cp /etc/apt/sources.list /etc/apt/sources.list_backup

Open the sources.list file to make changes

sudo gedit /etc/apt/sources.list

Edit the /etc/apt/sources.list file and add Aliyun mirror sources at the beginning of the file:

deb http://mirrors.aliyun.com/ubuntu/ bionic main restricted universe multiverse
deb http://mirrors.aliyun.com/ubuntu/ bionic-security main restricted universe multiverse
deb http://mirrors.aliyun.com/ubuntu/ bionic-updates main restricted universe multiverse
deb http://mirrors.aliyun.com/ubuntu/ bionic-proposed main restricted universe multiverse
deb http://mirrors.aliyun.com/ubuntu/ bionic-backports main restricted universe multiverse
deb-src http://mirrors.aliyun.com/ubuntu/ bionic main restricted universe multiverse
deb-src http://mirrors.aliyun.com/ubuntu/ bionic-security main restricted universe multiverse
deb-src http://mirrors.aliyun.com/ubuntu/ bionic-updates main restricted universe multiverse
deb-src http://mirrors.aliyun.com/ubuntu/ bionic-proposed main restricted universe multiverse
deb-src http://mirrors.aliyun.com/ubuntu/ bionic-backports main restricted universe multiverse

Refresh the list

sudo apt-get update
sudo apt-get upgrade
sudo apt-get install build-essential

Set up the key

sudo apt-key adv --keyserver 'hkp://keyserver.ubuntu.com:80' --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654

Install

sudo apt update
sudo apt install ros-melodic-desktop-full
Initialize rosdep (might fail easily)

If initialization fails, try using a mobile hotspot to connect to the network for rosdep init. If that doesn't work, follow step 6 to modify (if it still doesn't work, try running sudo rosdep init multiple times until there are no errors), complete the initialization, then proceed to configure the environment variables

sudo rosdep init
rosdep update
Set up environment variables
echo "source /opt/ros/melodic/setup.bash" >> ~/.bashrc
source ~/.bashrc
rosdeq error

Due to server reasons, you may encounter the following issue and need to modify the configuration file:

sudo rosdep init

ERROR: cannot download default sources list from: https://raw.githubusercontent.com/ros/rosdistro/master/rosdep/sources.list.d/20- default.list
Website may be down.
rosdep update
reading in sources list data from /etc/ros/rosdep/sources.list.d ERROR: error loading sources list:
('The read operation timed out')

Open the file containing the resource download function:

sudo gedit /usr/lib/python2.7/dist-packages/rosdep2/sources_list.py

Add

url="https://ghproxy.com/"+url
def download_rosdep_data(url):
"""
:raises: :exc:`DownloadFailure` If data cannot be
retrieved (e.g. 404, bad YAML format, server down).
"""
try:
url = "https://ghproxy.com/"+url
f = urlopen_gzip(url, timeout=DOWNLOAD_TIMEOUT)
text = f.read()
f.close()
data = yaml.safe_load(text)
if type(data) != dict:
raise DownloadFailure('rosdep data from [%s] is not a YAML dictionary' % (url))
return data
except (URLError, httplib.HTTPException) as e:
raise DownloadFailure(str(e) + '(%s)' % url)
except yaml.YAMLError as e:
raise DownloadFailure(str(e))

Everyone may have different URLs, "add https://gexxxxxx.com/ in front of the original path"

Modify DEFAULT_INDEX_URL in the /usr/lib/python2.7/dist-packages/rosdistro/init.py file:

sudo gedit /usr/lib/python2.7/dist-packages/rosdistro/init.py

DEFAULT_INDEX_URL ='https://ghproxy.com/https://raw.githubusercontent.com/ros/rosdistro/master/index-v4.yaml'

"""
line 72
"""

# default file to download with 'init' command in order to bootstrap
# rosdep
DEFAULT_INDEX_URL ='https://ghproxy.com/https://raw.githubusercontent.com/ros/rosdistro/master/index-v4.yaml'

Modify the address in the remaining (4) files, add http://ghproxy.com/ before http://raw.githubsercontent.com/

sudo gedit /usr/lib/python2.7/dist-packages/rosdep2/gbpdistro_support.py
//Modify the address on line 36
sudo gedit /usr/lib/python2.7/dist-packages/rosdep2/sources_list.py
//Modify the address on line 72
sudo gedit /usr/lib/python2.7/dist-packages/rosdep2/rep3.py
//Modify the address on line 39
sudo gedit /usr/lib/python2.7/dist-packages/rosdistro/manifest_provider/github.py
//Modify the address on line 68 and 119

Resolve the error of the fifth address of Hit

sudo gedit /usr/lib/python2.7/dist-packages/rosdep2/gbpdistro_support.py

Add the following code at line 204 (the first line under the function block)

gbpdistro_url = "https://ghproxy.com/" + gbpdistro_url
# Note that the double quotes of the proxy address in the original website are in Chinese. Copy-pasting directly may cause character recognition errors

If the error persists, try to modify it

sudo gedit /etc/resolv.conf

Comment out the existing nameserver line and add the following two lines:

nameserver 8.8.8.8 #google domain name server
nameserver 8.8.4.4 #google domain name server

Save and exit. Execute

sudo apt-get update

Then execute

sudo rosdep init

ERROR: default sources list file already exists:
/etc/ros/rosdep/sources.list.d/20-default.list Please delete if you wish to re-initialize

Solution: Execute the following command to delete the existing initialization file:

sudo rm /etc/ros/rosdep/sources.list.d/20-default.list

Run the following command again

sudo rosdep init

Installation of ROS function package

sudo apt-get install ros-melodic-moveit
sudo apt-get install ros-melodic-joint-state-publisher
sudo apt-get install ros-melodic-robot-state-publisher
sudo apt install ros-melodic-gazebo-ros-pkgs
sudo apt-get install ros-melodic-gazebo-ros-control
sudo apt-get install ros-melodic-joint-trajectory-controller
sudo apt-get install ros-melodic-industrial-core

Creation of ROS workspace

mkdir -p ~/inexbot/src
cd ~/inexbot/src
catkin_init_workspace

If you encounter

Creating symlink "/root/learn_ros_ws/src/CMakeLists.txt" pointing to "/opt/ros/melodic/share/catkin/cmake/toplevel.cmake"

in this case, run the following command

ls -al ~/inexbot/src

Then proceed to run the workspace initialization command

catkin_init_workspace
cd ../
catkin_make

Modify ~/.bashrc

gedit ~/.bashrc

Add the following line at the end of the file:

source ~/inexbot/devel/setup.bash

Copy all packages of inexbot to the inexbot/src directory

(The packages of inexbot are located in "02 Controller/Documents/Setting up Development Environment on a New Computer/ros/inexbot_diver")

Configuring moveit and the robot

Configure the urdf model of a robot using moveit, the generated configuration files are in the xxx_config folder. These files need to be modified.

Install moveit

Open a new terminal

sudo apt-get install ros-melodic-moveit
source /opt/ros/melodic/setup.bash
sudo apt-get install ros-melodic-moveit-resources

After the installation, in the terminal, enter the following code to load the robot's urdf

roslaunch moveit_setup_assistant setup_assistant.launch

ros

ros

ros

ros

ros

ros

ros

ros

ros

Copy the two folders from the inexbot_driver directory,

as well as the generated moveit files.

ros

Change all default moveit folder names in qj_ws/src/inexbot_support/launch/moveit_planning_execution.launch to 'qj_moveit' (the name of the moveit folder).

ros

ros

Change the joint names in the two .yaml files in inexbot_support/config to match the joint names in the urdf

ros

Change the content in the red box in qj_moveit/launch/qj_moveit_controller_manager.launch.xml to (find inexbot_support)/config/controllers.yaml

ros

Open the terminal

cd qj_ws
catkin_make
source devel/setup.bash
roslaunch inexbot_support moveit_planning_execution.launch sim:=false robot_ip:=192.168.1.13

Controlling the robot using moveit

1. Set goal state control

5

Click on "Plan" to generate a planned trajectory. The bottom will display the planned time (Time).

6

​Click on "Execute" to execute the planned trajectory. Alternatively, you can click on "Plan&Execute" to plan and execute immediately

2. Control through dragging the planner

​ Drag the green ball on the front end of the planner. When the cursor is placed on the ball, a 3D coordinate will appear below. Drag it to the desired point, then click on "Plan" to generate a planned trajectory. Click on "Execute" to execute the trajectory. Alternatively, you can click on "Plan&Execute" to plan and execute immediately

7

Controlling the robot through C++ programming

1. Create a ROS package to store the program files

cd ~/inexbot/src
catkin_create_pkg inexbot_code std_msgs rospy roscpp
cd ../
catkin_make

2. Joint space planning

Create moveit_joint_demo.c

Place the file in the ~/inexbot/src/inexbot_code/src directory

//moveit_joint_demo.c
#include <ros/ros.h>
#include <moveit/move_group_interface/move_group_interface.h>

int main(int argc, char **argv)
{
//ros initialization
ros::init(argc, argv, "moveit_joint_demo");
ros::AsyncSpinner spinner(1);
spinner.start();

//manipulator is the planning group set up through moveit
moveit::planning_interface::MoveGroupInterface arm("manipulator");

//Allowable error
arm.setGoalJointTolerance(0.001);
//Maximum acceleration
arm.setMaxAccelerationScalingFactor(0.2);
//Maximum velocity
arm.setMaxVelocityScalingFactor(0.2);

//Set the goal_state to control the robot arm to move back to the home position
//'home' is a pre-defined position in moveit
arm.setNamedTarget("home");
//Move
arm.move();
sleep(1);
//Set the angles of the six axes in joint space
double targetPose[6] = {0.391410, -0.676384, -0.376217, 0.0, 1.052834, 0.454125};
std::vector<double> joint_group_positions(6);
joint_group_positions[0] = targetPose[0];
joint_group_positions[1] = targetPose[1];
joint_group_positions[2] = targetPose[2];
joint_group_positions[3] = targetPose[3];
joint_group_positions[4] = targetPose[4];
joint_group_positions[5] = targetPose[5];

arm.setJointValueTarget(joint_group_positions);
arm.move();
sleep(1);

//Control the robot arm to move back to the home position
arm.setNamedTarget("home");
arm.move();
sleep(1);

ros::shutdown();

return 0;
}

Modify CMakeLists.txt file

Add the following lines above the install tag:

add_executable(moveit_joint_demo src/moveit_joint_demo.cpp)
target_link_libraries(moveit_joint_demo ${catkin_LIBRARIES})
#############
## Install ##
#############

Compile the code files

cd ~/inexbot
catkin_make

Run

rosrun inexbot_code moveit_joint_demo