forked from cesar.alejandro/oscillation_ctrl
Update 'README.md'
This commit is contained in:
parent
859cd81e4e
commit
3acb9b046e
123
README.md
123
README.md
|
@ -1,3 +1,124 @@
|
||||||
# oscillation_ctrl
|
# oscillation_ctrl
|
||||||
|
|
||||||
Repo containing oscillation damping controller for tether missions + instructions how to to set up
|
Repo containing oscillation damping controller for tether missions + instructions how to to set up
|
||||||
|
|
||||||
|
Cesar Rodriguez
|
||||||
|
February 2022
|
||||||
|
|
||||||
|
Steps to recreate stable PX4 environment + working repo
|
||||||
|
|
||||||
|
#STEP 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 YOUR 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 LIB DATASETS
|
||||||
|
cd ~/catkin_ws
|
||||||
|
sudo ./src/mavros/mavros/scripts/install_geographiclib_datasets.sh
|
||||||
|
- BUILD SOURCE
|
||||||
|
cd ~/catkin_ws
|
||||||
|
catkin build
|
||||||
|
|
||||||
|
|
||||||
|
#STEP 2) PX4 Environment Development
|
||||||
|
|
||||||
|
- DOWNLOAD PX4 SOURCE CODE
|
||||||
|
git clone https://github.com/PX4/PX4-Autopilot.git --recursive
|
||||||
|
- RUN UBUNTU.SH
|
||||||
|
bash ./PX4-Autopilot/Tools/setup/ubuntu.sh
|
||||||
|
Restart computer after it is done
|
||||||
|
- BUILD ROS/GAZEBO: Gets Gazebo9
|
||||||
|
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
|
||||||
|
- Build jMAVSim and Gazebo
|
||||||
|
cd ~/PX4-Autopilot
|
||||||
|
make px4_sitl jmavsim
|
||||||
|
%%% May need to open QGroundControl for it to work %%%
|
||||||
|
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
|
||||||
|
|
||||||
|
#STEP 3) This is Cesar stuff, need to do stuff to rebuild oscillation_ctrl
|
||||||
|
- INSTALL XTERM
|
||||||
|
sudo apt-get update -y
|
||||||
|
sudo apt-get install -y xterm
|
||||||
|
-INSTALL MAVROS_CONTROLLERS
|
||||||
|
cd ~/catkin_ws/src
|
||||||
|
clone repo:
|
||||||
|
git clone https://github.com/Jaeyoung-Lim/mavros_controllers
|
||||||
|
Download dependencies:
|
||||||
|
cd ~/catkin_ws
|
||||||
|
wstool merge -t src src/mavros_controllers/dependencies.rosinstall
|
||||||
|
wstool update -t src -j4
|
||||||
|
rosdep install --from-paths src --ignore-src -y --rosdistro $ROS_DISTRO
|
||||||
|
catkin build
|
||||||
|
source ~/catkin_ws/devel/setup.bash
|
||||||
|
~Troubleshooting: https://github.com/Jaeyoung-Lim/mavros_controllers
|
||||||
|
-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
|
||||||
|
-ROMFS/PX4FMU_COMMON
|
||||||
|
copy (or add) files in oscillation_ctrl/airframes to PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/airframes
|
||||||
|
add file name to CmakeLists.txt in same 'airframe' folder (with number)
|
||||||
|
add airframe name in ~/PX4-Autopilot/platforms/posix/cmake/sitl_target.cmake (no number!)
|
||||||
|
-LAUNCH FILES
|
||||||
|
ccopy (or add) files from px4_launch directory to ~/PX4-Autopilot/launch
|
||||||
|
-MAVROS
|
||||||
|
- in px4.launch, replace:
|
||||||
|
<arg name="fcu_url" default="/dev/ttyACM0:57600" />
|
||||||
|
<arg name="gcs_url" default="udp-b://127.0.0.1:14555@14550" />
|
||||||
|
- with:
|
||||||
|
<arg name="fcu_url" default="udp://:14551@192.168.1.91:14556" />
|
||||||
|
<arg name="gcs_url" default="udp-b://127.0.0.1:14555@14550" />
|
||||||
|
- 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
|
||||||
|
|
||||||
|
#JINJA TETHER 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)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue