This repository if for deepControl.
The Deep Neural Network (DNN) Controller is a two hidden layer Neural Network with 64 neurons in each layer.
The quadrotor state-space equation is a 12 dimensional vector
s = [x,y,z, vx,vy,vz, roll,pitch,yaw, rs,ps,ys]
where
- x,y,z is the position
- vx, vy, vz is the linear velocities
- roll,pitch,yaw are the Euler Angles
- rs,ps,ys are the angular velocities
This high level controller on the quadrotor takes in the state and outputs the controls:
u = [roll_commanded, pitch_commanded, yaw_rate, thrust_commanded]
The dynamics of the quadrotor dictate that the yaw motion is decoupled from the roll and pitch motion. Therefore we keep the yaw as constant. The DNN takes in the state and outputs the three controls: [roll_commanded, pitch_commanded, thrust_commanded]
The DNN weights are learned by using supervised learning. The data for learning is generated by using Model Predictive Controller running on the quadrotor.
The learned controller can be implemented in either C++ or python.
The DNN has 2 hidden layers each with 64 neurons.
Input
The desired position is denoted by [x_des, y_des, z_des]
. The input to the DNN is given as
X = [x_des-x, y_des-y, z_des-z, vx, vy, vz, roll, pitch, rs, ps]
This input is fed to the first layer:
o1 = relu(W1.X + B1)
where relu is the activation function, W1 is the weight matrix and B1 is the bias, of layer 1.
Similarly for the 2nd layer.
o2 = relu(W2.o1 + B2)
Output
The output from the DNN controller is [roll, pitch, thrust]
For the output layer the activation function used is tanh as it bounds the output between [-1, 1].
y = tanh(W3.o2 + B3)
The thrust is output is scaled up according to the weight of the quadrotor.
The tracking performance of the DNN is at par with the MPC controller.
The python/mav_deepControl.py
is the controller written in python with controller weight in python/wt
The C++ controller is located at cpp/src/mav_deepControl.cpp
with weights in cpp/include
. The C++ controller uses Eigen
libraries for matrix arithmetic.
Requirements ROS-Kinetic, catkin tools, Eigen3
- Install catkin tools
$ sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu `lsb_release -sc` main" > /etc/apt/sources.list.d/ros-latest.list' $ wget http://packages.ros.org/ros.key -O - | sudo apt-key add -
- Clone the deepControl repository
git clone https://github.com/pratyusv/deepControl.git cd ./deepControl git submodule update --init --recursive
- Build the catkin workspace
catkin build
Ensure that the ros environment is included in the bash profile of the shell. If it is not included add to ~/.bashrc
source /opt/ros/kinetic/setup.sh
Go to the catkin workspace of the deepControl folder.
cd ./deepControl/catkin_ws/src
All the terminals in the below step are created from the above path.
-
Launch the
rotors_simulator
in the terminalroslaunch rotors_gazebo mav.launch mav_name:=f450
Unpause the physics of the gazebo by clicking on the play button.
-
In a new Terminal launch the Non-Linear MPC controller:
roslaunch mav_nonlinear_mpc mav_nonlinear_mpc_sim.launch mav_name:=f450
The mpc commands are intially published on the topic:
/f450/command/roll_pitch_yawrate_thrust
. We remap these controls to topic/f450/rpyth
. These frees up the/f450/command/roll_pitch_yawrate_thrust
topic to publish the DNN controlls.This remapping is done in the mav_nonlinear_mpc_sim.launch file.
<remap from="command/roll_pitch_yawrate_thrust" to="rpyth"/>
-
In a new terminal run the trajectory generator.
roslaunch mav_trajectory_generation_ros my_node.launch mav_name:=f450
-
In a new terminal run the DNN controller.
cd ./dnn_mpc python follow_xy.py
-
In a new terminal kill the tracker rosnode. The quadorotor will start following the trajectory once the tracker node is killed.
rosnode kill /f450/tracking_node