forked from cesar.alejandro/oscillation_ctrl
Update 'README.md'
This commit is contained in:
parent
937fd75fee
commit
130f1e2561
71
README.md
71
README.md
|
@ -2,6 +2,8 @@
|
|||
|
||||
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
|
||||
|
@ -10,6 +12,8 @@ February 2022
|
|||
|
||||
Steps to recreate stable PX4 environment + working repo
|
||||
|
||||
# Setup
|
||||
|
||||
## 1) Installing ROS Melodic
|
||||
|
||||
### Setup sources.list
|
||||
|
@ -50,24 +54,26 @@ Initilize rosdep:
|
|||
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](https://docs.px4.io/main/en/dev_setup/dev_env_linux_ubuntu.html#rosgazebo). Then:
|
||||
|
||||
#### Download QGroundControl from:
|
||||
https://docs.qgroundcontrol.com/master/en/releases/daily_builds.html
|
||||
#### 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
|
||||
|
||||
#### 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
|
||||
|
||||
## 3) Set up oscillation_ctrl
|
||||
### Install xterm
|
||||
sudo apt-get update -y
|
||||
|
@ -77,6 +83,24 @@ Install [PX4 Firmware](https://docs.px4.io/main/en/dev_setup/dev_env_linux_ubunt
|
|||
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
|
||||
|
||||
|
@ -86,7 +110,7 @@ copy (or add) files in _oscillation_ctrl/models_ and _oscillation_ctrl/worlds_ t
|
|||
### 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
|
||||
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)
|
||||
|
||||
|
@ -113,23 +137,28 @@ Finally, source your setup.bash file
|
|||
cd ~/catkin_ws
|
||||
source devel/setup.bash
|
||||
|
||||
## JINJA TETHER FILE
|
||||
## 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. (Currently, it should be added after Ln 290 - may change in future)
|
||||
- __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
|
||||
|
||||
- This should be added in the line below VERBATIM in the add_custom_command function, which should be Ln 290). It should be part of the add_custom_command() after the 'else' statement
|
||||
_oscillation_ctrl/px4_setup/CMakeLists.txt has these changes therefore all that is needed is:
|
||||
|
||||
## ROS NODES
|
||||
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.
|
||||
|
||||
|
@ -220,4 +249,14 @@ To run the simulation with a tethered payload headless mode and perform a step t
|
|||
|
||||
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.
|
||||
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
|
||||
|
|
Loading…
Reference in New Issue