oscillation_ctrl/README.md

232 lines
8.3 KiB
Markdown
Raw Normal View History

2022-03-01 13:35:05 -04:00
# oscillation_ctrl
2022-03-04 14:22:39 -04:00
Repo containing oscillation damping controller for tether missions + instructions how to to set up
Cesar Rodriguez
cesar.rodriguez@spirirobotics.com
February 2022
Steps to recreate stable PX4 environment + working repo
## 1) Installing ROS Melodic
2022-07-05 11:55:28 -03:00
### Setup sources.list
2022-03-04 14:22:39 -04:00
sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu $(lsb_release -sc) main" > /etc/apt/sources.list.d/ros-latest.list'
2022-07-05 11:55:28 -03:00
### Setup keys
2022-03-04 14:22:39 -04:00
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 -
2022-07-05 11:55:28 -03:00
### Installation
2022-03-04 14:22:39 -04:00
sudo apt update
sudo apt install ros-melodic-desktop-full
2022-07-05 11:55:28 -03:00
### Environment setup
2022-03-04 14:22:39 -04:00
echo "source /opt/ros/melodic/setup.bash" >> ~/.bashrc
2022-07-05 11:55:28 -03:00
### Dependencies
2022-03-04 14:22:39 -04:00
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
2022-07-05 11:55:28 -03:00
### PX4 Dependencies
2022-03-04 14:22:39 -04:00
sudo apt-get install python-catkin-tools python-rosinstall-generator -y
wstool init ~/catkin_ws/src
### MAVLINK
rosinstall_generator --rosdistro melodic mavlink | tee /tmp/mavros.rosinstall
### MAVROS
rosinstall_generator --upstream mavros | tee -a /tmp/mavros.rosinstall
2022-07-05 11:55:28 -03:00
### Create workspace and deps
2022-03-04 14:22:39 -04:00
cd ~/catkin_ws
wstool merge -t src /tmp/mavros.rosinstall
wstool update -t src -j4
rosdep install --from-paths src --ignore-src -y
2022-07-05 11:55:28 -03:00
### Install geographic datasets
2022-03-04 14:22:39 -04:00
cd ~/catkin_ws
sudo ./src/mavros/mavros/scripts/install_geographiclib_datasets.sh
2022-07-05 11:55:28 -03:00
### Build source
2022-03-04 14:22:39 -04:00
cd ~/catkin_ws
catkin build
## 2) PX4 Environment Development
2022-07-05 11:55:28 -03:00
### Download PX4 source code
2022-03-04 14:22:39 -04:00
git clone https://github.com/PX4/PX4-Autopilot.git --recursive
2022-07-05 11:55:28 -03:00
### Run ubuntu.sh
2022-03-04 14:22:39 -04:00
bash ./PX4-Autopilot/Tools/setup/ubuntu.sh
#Restart computer after it is done
2022-07-05 11:55:28 -03:00
### Build ROS and Gazebo - This defaults to Gazebo9
2022-03-04 14:22:39 -04:00
wget https://raw.githubusercontent.com/PX4/Devguide/master/build_scripts/ubuntu_sim_ros_melodic.sh
bash ubuntu_sim_ros_melodic.sh
#### Download QGroundControl from:
https://docs.qgroundcontrol.com/master/en/releases/daily_builds.html
2022-04-13 15:17:40 -03:00
#### Build Gazebo Sim
2022-03-04 14:22:39 -04:00
cd ~/PX4-Autopilot
make px4_sitl gazebo
#### Create 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
2022-07-05 11:55:28 -03:00
## 3) Set up oscillation_ctrl
### Install xterm
2022-03-04 14:22:39 -04:00
sudo apt-get update -y
sudo apt-get install -y xterm
2022-07-05 11:55:28 -03:00
### Clone oscillation_ctrl
cd ~catkin_ws/src
git clone https://git.spirirobotics.com/cesar.alejandro/oscillation_ctrl.git
### 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/* 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
2022-03-04 14:22:39 -04:00
In catkin_ws (or any working directory) add to devel/setup.bash:
2022-07-05 11:55:28 -03:00
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
2022-03-04 14:33:03 -04:00
2022-07-05 11:55:28 -03:00
cd $CURRENT_DIR
2022-03-04 14:33:03 -04:00
2022-03-04 14:22:39 -04:00
## JINJA TETHER FILE
2022-03-08 11:20:19 -04:00
- _spiri_with_tether.sdf.jinja_ can be altered to create desired tether model
2022-04-18 10:10:17 -03:00
- 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
2022-03-04 14:22:39 -04:00
- 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)
2022-03-08 11:20:19 -04:00
- __IMPORTANT:__ in order for jinja file to work, the following needs to be added to the _CMakeLists.txt_ (Ln 288 - may change in future) in the _~/PX4-Autopilot/Tools/sitl_gazebo_ folder:
2022-07-05 11:55:28 -03:00
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
)
2022-03-08 11:20:19 -04:00
- This should be added in the line below VERBATIM in the add_custom_command function, which should be Ln 288)
2022-03-04 14:22:39 -04:00
2022-03-07 11:17:20 -04:00
## ROS NODES
2022-07-05 12:01:50 -03:00
### 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 step test.
__Publishes to__:
2022-07-05 11:55:28 -03:00
/status/twoBody_status # localization and angles
2022-07-05 12:05:12 -03:00
/status/load_angles # payload angles (and tates) relative to vehicle
2022-07-05 11:55:28 -03:00
/status/path_follow # boolean to run trajectory test
2022-07-05 12:01:50 -03:00
__Subscribes to__:
2022-07-05 11:55:28 -03:00
none
2022-07-05 12:01:50 -03:00
### 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__:
2022-07-05 11:55:28 -03:00
none
2022-07-05 12:01:50 -03:00
__Subscribes to__:
2022-07-05 11:55:28 -03:00
/reference/waypoints
2022-07-05 12:01:50 -03:00
### ref_signalGen.py
takes in desired position (xd) and determines smooth path trajectory.
__Publishes to__:
2022-07-05 12:05:12 -03:00
/reference/path # smooth path
/reference/flatsetpoint # needed to determine thrust
2022-07-05 12:01:50 -03:00
__Subscribes to__:
2022-07-05 11:55:28 -03:00
/status/load_angles
/mavros/local_position/pose
/mavros/local_position/velocity_body
/mavros/imu/data
/mavros/state
/reference/waypoints
2022-07-05 12:01:50 -03:00
### 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__:
2022-07-05 12:05:12 -03:00
/command/quaternions # attitude commands
2022-07-05 12:01:50 -03:00
__Subscribes to__:
2022-07-05 11:55:28 -03:00
/status/load_angles
/reference/path
/mavros/local_position/pose
/mavros/local_position/velocity_body
/mavros/imu/data
2022-07-05 12:01:50 -03:00
2022-03-07 13:51:46 -04:00
- node from _mavros_controllers/geometric_controller_ subscribes to _/reference/flatsetpoint_ to determine thrust commands which are published to _command/bodyrate_command_ by default
2022-07-05 12:01:50 -03:00
### 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__:
2022-07-05 12:05:12 -03:00
mavros/setpoint_position/local # needed to hover @ set height
mavros/setpoint_raw/attitude # attitude and thrust commands
2022-07-05 12:01:50 -03:00
__Subscribes to__:
2022-07-05 11:55:28 -03:00
/command/quaternions
/command/bodyrate_command
/mavros/state
2022-03-07 11:17:20 -04:00
2022-04-18 10:10:17 -03:00
## Launching simulation
2022-07-05 12:01:50 -03:00
To launch a simulation, run the following command:
2022-07-05 11:55:28 -03:00
roslaunch oscillation_ctrl oscillation_damp.launch
2022-07-05 12:01:50 -03:00
This simulation is set to have a Spiri Mu hover at an alitude of 5 m.
The launch file itself has two usable arguments:
2022-04-25 17:14:06 -03:00
__model:__
2022-07-05 12:05:12 -03:00
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
2022-04-25 17:14:06 -03:00
__test:__
2022-07-05 12:05:12 -03:00
none # default
step # step input - default is 5 m
square # square trajectory
2022-07-05 11:55:28 -03:00
To run the simulation with a tethered payload headless mode and perform a step test:
2022-03-07 11:17:20 -04:00
2022-07-05 12:21:51 -03:00
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.