Update 'README.md'
This commit is contained in:
parent
9284b4b7ba
commit
3ca7da75b6
167
README.md
167
README.md
|
@ -2,8 +2,6 @@
|
|||
|
||||
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
|
||||
|
@ -12,69 +10,13 @@ February 2022
|
|||
|
||||
Steps to recreate stable PX4 environment + working repo
|
||||
|
||||
### WARNING
|
||||
|
||||
Currently repo is only for Ubuntu 18.04 and ROS Melodic, work is being made to be upgraded to Ubuntu 20.04 and ROS Noetic
|
||||
|
||||
# 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
|
||||
### MAVLINK
|
||||
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](https://docs.px4.io/main/en/dev_setup/dev_env_linux_ubuntu.html#rosgazebo). 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
|
||||
## 1) Set up oscillation_ctrl
|
||||
### Install xterm
|
||||
sudo apt-get update -y
|
||||
sudo apt-get install -y xterm
|
||||
|
@ -83,44 +25,63 @@ cd to desired directory to install QGroundControl. For example, Desktop
|
|||
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:
|
||||
### Run bash script and build
|
||||
bash /.oscillation_ctrl/px4_setup/ubuntu_sim_ros_melodic.sh
|
||||
This bash script is taken from PX4 Firmware but sets certain versions of dependencies to work with oscillation_ctrl. It also installs common ROS dependencies, ROS Melodic, Gazebo 9, and MAVROS. It should build oscillation_ctrl and add the source path to your .bashrc. If it does not, then run:
|
||||
|
||||
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
|
||||
cd ~/catkin_ws
|
||||
catkin build
|
||||
source devel/setup.bash
|
||||
|
||||
#### Now, we finish building the PX4 package
|
||||
If you do not want to source every time, add 'source ~/catkin_ws/devel/setup.bash' to your .bashrc
|
||||
|
||||
## 2) PX4 Environment Development
|
||||
Install PX4 firmware and dependencies:
|
||||
|
||||
git clone https://github.com/PX4/PX4-Autopilot.git --recursive
|
||||
git checkout 601c588294973caf105b79a23f7587c6b991bb05
|
||||
bash ./PX4-Autopilot/Tools/setup/ubuntu.sh
|
||||
|
||||
There will be prompts on the screen, hit 'u' and 'enter' as they come up.
|
||||
|
||||
### Add models, world, and airframe files
|
||||
To add the necessary Spiri Mu files to PX4, run:
|
||||
|
||||
cd ca
|
||||
bash /.oscillation_ctrl/px4_setup/px4_bash.sh
|
||||
|
||||
### Add airframes to cmake targets
|
||||
add 'spiri' and 'spiri_with_tether' airframe names in _~/PX4-Autopilot/platforms/posix/cmake/sitl_target.cmake_ under set(models...
|
||||
|
||||
__do not add their airframe number! e.i. 4000 or 4001__
|
||||
|
||||
### Download QGroundControl:
|
||||
cd to desired directory to install QGroundControl. For example, Desktop.
|
||||
|
||||
cd ~/<example_Desktop>
|
||||
wget https://github.com/mavlink/qgroundcontrol/releases/download/v4.2.0/QGroundControl.AppImage
|
||||
chmod +x QGroundControl.AppImage
|
||||
|
||||
### Finish Building PX4 package
|
||||
cd ~/PX4-Autopilot
|
||||
DONT_RUN=1 make px4_sitl_default gazebo
|
||||
|
||||
If if fails and you see
|
||||
|
||||
gzerver: symbol lookup error...
|
||||
|
||||
then run:
|
||||
|
||||
sudo apt upgrade libignition-math2
|
||||
|
||||
If all is good, run:
|
||||
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.
|
||||
PX4 should launch with MAVROS
|
||||
|
||||
### 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:
|
||||
|
||||
|
@ -144,16 +105,6 @@ Finally, source your setup.bash file
|
|||
- 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.
|
||||
|
@ -262,3 +213,19 @@ __pload_mass:__ sets the payload mass in simulation without having to change the
|
|||
|
||||
## Frequent Issues
|
||||
Will populate this section with frequently faces issues
|
||||
|
||||
### No header files error:
|
||||
In oscillation_ctrl/CMakeLists.txt, change:
|
||||
|
||||
add_dependencies(pathFollow_node ${${PROJECT_NAME}EXPORTEDTARGETS} ${catkin_EXPORTED_TARGETS})
|
||||
|
||||
to:
|
||||
|
||||
add_dependencies(pathFollow_node oscillation_ctrl_generate_messages_cpp)
|
||||
|
||||
### Cannot build px4_sitl
|
||||
Normally, this is solved by running:
|
||||
|
||||
make clean
|
||||
|
||||
And redo command you were trying to run. If problem persists, rerun ubuntu_sim_ros_melodic.sh and ubuntu.sh and try again.
|
Loading…
Reference in New Issue