Repo containing oscillation damping controller for tethered missions + instructions how to set up
Go to file
cesar a99ba1059c Changing airframe files 2022-09-15 16:01:31 -03:00
airframes Changing airframe files 2022-09-15 16:01:31 -03:00
config Lastest changes to algorithm + adding airframes to work with Ubuntu 20.04 2022-09-14 14:19:12 -03:00
launch Updated launch file to be able to change payload mass in simulation 2022-09-14 15:58:08 -03:00
models Updating airframes to work with version 1.13dev of PX4 Firmware 2022-08-31 17:29:05 -03:00
msg More improvements to controller 2022-08-18 15:29:26 -03:00
px4_launch More improvements to controller 2022-08-18 15:29:26 -03:00
px4_setup CMake list now has two different ways to make the header files for custom messages 2022-09-15 14:39:30 -03:00
src Lastest changes to algorithm + adding airframes to work with Ubuntu 20.04 2022-09-14 14:19:12 -03:00
srv Added service to set waypoints 2022-03-18 11:50:09 -03:00
worlds Added world and drone models to repo 2022-03-04 13:29:37 -04:00
.gitignore CMake list now has two different ways to make the header files for custom messages 2022-09-15 14:37:36 -03:00
CMakeLists.txt CMake list now has two different ways to make the header files for custom messages 2022-09-15 14:37:36 -03:00
README.md Update 'README.md' 2022-09-14 11:57:20 -07:00
package.xml Merging branches 2022-04-18 10:10:17 -03:00

README.md

oscillation_ctrl

Repo containing oscillation damping controller for tether missions + instructions how to to set up

WARNING: Currently repo is only for Ubuntu 18.04 and ROS Melodic, work is being made to be upgrade to Ubuntu 20.04 and ROS Noetic

Cesar Rodriguez

cesar.rodriguez@spirirobotics.com

February 2022

Steps to recreate stable PX4 environment + working repo

Setup

1) Installing ROS Melodic

Setup sources.list

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

Setup keys

sudo apt install curl # if you haven't already installed curl
curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add -

Installation

sudo apt update
sudo apt install ros-melodic-desktop-full

Environment setup

echo "source /opt/ros/melodic/setup.bash" >> ~/.bashrc

Dependencies

sudo apt install python-rosdep python-rosinstall python-rosinstall-generator python-wstool build-essential

Initilize rosdep:

sudo apt install python-rosdep
sudo rosdep init
rosdep update

PX4 Dependencies

sudo apt-get install python-catkin-tools python-rosinstall-generator -y
wstool init ~/catkin_ws/src
rosinstall_generator --rosdistro melodic mavlink | tee /tmp/mavros.rosinstall

MAVROS

rosinstall_generator --upstream mavros | tee -a /tmp/mavros.rosinstall

Create workspace and deps

cd ~/catkin_ws
wstool merge -t src /tmp/mavros.rosinstall
wstool update -t src -j4
rosdep install --from-paths src --ignore-src -y

Install geographic datasets

cd ~/catkin_ws
sudo ./src/mavros/mavros/scripts/install_geographiclib_datasets.sh

Build source

cd ~/catkin_ws	
catkin build

2) PX4 Environment Development

Install PX4 firmware and ROS melodic dependencies:

git clone https://github.com/PX4/PX4-Autopilot.git --recursive
git checkout 601c588294973caf105b79a23f7587c6b991bb05
bash ./PX4-Autopilot/Tools/setup/ubuntu.sh

Install PX4 Firmware. Then:

Download QGroundControl:

cd to desired directory to install QGroundControl. For example, Desktop

cd ~/<desired_directory>
wget https://github.com/mavlink/qgroundcontrol/releases/download/v4.2.0/QGroundControl.AppImage
chmod +x QGroundControl.AppImage

Build Gazebo Sim

cd ~/PX4-Autopilot
make px4_sitl gazebo

3) Set up oscillation_ctrl

Install xterm

sudo apt-get update -y
sudo apt-get install -y xterm

Clone oscillation_ctrl

cd ~/catkin_ws/src
git clone https://git.spirirobotics.com/cesar.alejandro/oscillation_ctrl.git

To get the specific version of mavros_msgs for oscillation_ctrl:

cp -R ~/catkin_ws/src/oscillation_ctrl/px4_setup/rosinstall.txt /tmp/mavros.rosinstall
wstool merge -t src /tmp/mavros.rosinstall
wstool update -t src -j4
rosdep install --from-paths src --ignore-src -y
catkin build

Now, we finish building the PX4 package

cd ~/PX4-Autopilot
DONT_RUN=1 make px4_sitl_default gazebo
source Tools/setup_gazebo.bash $(pwd) $(pwd)/build/px4_sitl_default
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:$(pwd)
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:$(pwd)/Tools/sitl_gazebo
roslaunch px4 posix_sitl.launch

If this works, we can move on.

Add files to tools/sitl_gazebo

copy (or add) files in oscillation_ctrl/models and oscillation_ctrl/worlds to PX4-Autopilot/Tools/sitl_gazebo/models and PX4-Autopilot/Tools/sitl_gazebo/worlds respectively

cp -R ~/catkin_ws/src/oscillation_ctrl/models/* ~/PX4-Autopilot/Tools/sitl_gazebo/models
cp -R ~/catkin_ws/src/oscillation_ctrl/worlds/* ~/PX4-Autopilot/Tools/sitl_gazebo/worlds

Add files to ROMFS/px4mu_common

copy (or add) files in oscillation_ctrl/airframes to PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/airframes

cp -R ~/catkin_ws/src/oscillation_ctrl/airframes/18.04/* ~/PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/airframes

add model names to CmakeLists.txt in same 'airframe' folder (with number... 4000_spiri and 4001_spiri_with_tether)

add airframe name in ~/PX4-Autopilot/platforms/posix/cmake/sitl_target.cmake (no number!)

Add necessary launch files

this should not be a necessary step and will be changed in the future

copy (or add) files from px4_launch directory to '~/PX4-Autopilot/launch'

cp -R ~/catkin_ws/src/oscillation_ctrl/px4_launch/* ~/PX4-Autopilot/launch

Change devel/setup.bash

In catkin_ws (or any working directory) add to devel/setup.bash:

CURRENT_DIR=$(pwd)
cd ~/PX4-Autopilot
source Tools/setup_gazebo.bash $(pwd) $(pwd)/build/px4_sitl_default
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:$(pwd)
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:$(pwd)/Tools/sitl_gazebo

cd $CURRENT_DIR

Finally, source your setup.bash file

cd ~/catkin_ws
source devel/setup.bash

Jinja tether file

  • spiri_with_tether.sdf.jinja can be altered to create desired tether model

  • changes need to be made in px4 directory and will only take effect after running: "make px4_sitl gazebo"

    • can do "DONT_RUN=1 make px4_sitl gazebo" to avoid starting px4 shell and gazebo
  • First two elements can be changed to tweak tether parameters

    • number_elements: number of segments tether will be composed of
    • tl: segment length (should be no shorter than 0.3 meters)
  • IMPORTANT: in order for jinja file to work, the following needs to be added to the CMakeLists.txt in the ~/PX4-Autopilot/Tools/sitl_gazebo folder. This creates a custom command to build the tether file whenever a change is done to it.

      COMMAND
      	${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py models/spiri_with_tether/spiri_with_tether.sdf} ${CMAKE_CURRENT_SOURCE_DIR}
      DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py models/spiri_with_tether/spiri_with_tether.sdf
      VERBATIM
    

_oscillation_ctrl/px4_setup/CMakeLists.txt has these changes therefore all that is needed is:

cp -R ~/catkin_ws/src/oscillation_ctrl/px4_setup/CMakeLists.txt ~/PX4-Autopilot/Tools/sitl_gazebo/

oscillation_ctrl info

Info pertaining to oscillation_ctrl repo such as what the ROS nodes do, different ROS parameters, etc.

ROS Nodes

LinkState.py

determines payload load angles and their rates (theta and phi) using Gazebo (needs to be made more robust), as well as determines tether length and keeps track of variables needed in case of a step or square test.

Publishes to:

/status/twoBody_status # no longer used but keeps track of payload and vehicle position
/status/load_angles    # payload angles (and states) relative to vehicle
/status/path_follow    # boolean to run trajectory test

Subscribes to:

none

wpoint_tracker.py

Sets original waypoints to be (in meters): [x=0,y=0,z=5]. This node listens to topic to keep track of desired waypoints. If any other node wants to change the waypoints, they publish to "reference/waypoints" and wpoint_tracker creates these new waypoints.

Publishes to:

none

Subscribes to:

/reference/waypoints 

ref_signalGen.py

takes in desired position (xd) and determines smooth path trajectory.

Publishes to:

/reference/path         # smooth path

Subscribes to:

/status/load_angles
/mavros/local_position/pose
/mavros/local_position/velocity_body
/mavros/imu/data
/mavros/state
/reference/waypoints

klausen_control.py

determines forces on drone needed based on smooth path and feedback to dampen oscillations. From the forces needed, it publishes attitude commands.

Publishes to:

/command/att_target # attitude commands

Subscribes to:

/status/load_angles
/reference/path
/mavros/local_position/pose
/mavros/local_position/velocity_body
/mavros/imu/data

set_ploadmass.py

sets the payload mass to be pload_mass value in the spiri_param.yaml

path_follow.cpp

sets the vehicle in OFFBOARD mode (PX4) and takes off to a set height for 25 seconds before starting to publish attitude and thrust commands.

Publishes to:

mavros/setpoint_position/local # needed to hover @ set height	
mavros/setpoint_raw/attitude   # attitude and thrust commands 	

Subscribes to:

/command/att_target	
/command/bodyrate_command	
/mavros/state

Launching simulation

To launch a simulation, run the following command:

roslaunch oscillation_ctrl oscillation_damp.launch

This simulation is set to have a Spiri Mu hover at an alitude of 5 m. The launch file itself has two usable arguments:

model:

spiri_with_tether           # Spiri Mu with a tethered payload			
spiri                       # Spiri Mu without tethered paylaod
headless_spiri_with_tether  # headless mode: launches with no Gazebo GUI. This is the default model

test:

none   # default
step   # step input - default is 5 m
square # square trajectory

To run the simulation with a tethered payload headless mode and perform a step test:

roslaunch oscillation_ctrl oscillation_damp.launch model:=headless_spiri_with_tether test:=step

Whenever the oscillation_ctrl is used, the scripts are written such that the vehicle will hover for about 30 seconds in "Position Mode". This is used to take advantage of the takeoff procedure PX4 has, as this controller assumes the vehicle is already in flight when determining the necessary thrust.

ROS parameters

All these values will be under the '/status/' namespace during simulation

use_ctrl: needs to be set to false to take off. Once Spiri has reached desired altitude, it get be set to 'true' to use oscillation damping controller. This is needed as PX4 has a takeoff procedure which is neglected when using the oscillation damping controller due to attitude setpoints needed a thrust value

pload_mass: sets the payload mass in simulation without having to change the spiri_with_tether jinja file (which needs px4 package to be rebuilt in order to make changes)

Frequent Issues

Will populate this section with frequently faces issues