diff --git a/README.md b/README.md index 3c3af7a..1912ab7 100644 --- a/README.md +++ b/README.md @@ -2,68 +2,76 @@ Repo containing oscillation damping controller for tether missions + instructions how to to set up -Cesar Rodriguez +Cesar Rodriguez + +cesar.rodriguez@spirirobotics.com + February 2022 Steps to recreate stable PX4 environment + working repo -#STEP 1) Installing ROS Melodic +## 1) Installing ROS Melodic -- SETUP SOURCES.LIST +### 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 +### 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 +### INSTALLATION sudo apt update sudo apt install ros-melodic-desktop-full -- ENVIRONMENT SETUP +### ENVIRONMENT SETUP echo "source /opt/ros/melodic/setup.bash" >> ~/.bashrc -- DEPENDENCIES +### 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 +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 +### MAVLINK rosinstall_generator --rosdistro melodic mavlink | tee /tmp/mavros.rosinstall -- MAVROS +### MAVROS rosinstall_generator --upstream mavros | tee -a /tmp/mavros.rosinstall -- CREATE WORKSPACE AND DEPS +### 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 +### INSTALL GEOGRAPHIC LIB DATASETS cd ~/catkin_ws sudo ./src/mavros/mavros/scripts/install_geographiclib_datasets.sh -- BUILD SOURCE +### BUILD SOURCE cd ~/catkin_ws catkin build +## 2) PX4 Environment Development -#STEP 2) PX4 Environment Development - -- DOWNLOAD PX4 SOURCE CODE +### DOWNLOAD PX4 SOURCE CODE git clone https://github.com/PX4/PX4-Autopilot.git --recursive -- RUN UBUNTU.SH + +### RUN UBUNTU.SH bash ./PX4-Autopilot/Tools/setup/ubuntu.sh - Restart computer after it is done -- BUILD ROS/GAZEBO: Gets Gazebo9 + #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: + +#### Download QGroundControl from: https://docs.qgroundcontrol.com/master/en/releases/daily_builds.html -- Build jMAVSim and Gazebo + +#### Build jMAVSim and Gazebo cd ~/PX4-Autopilot make px4_sitl jmavsim - %%% May need to open QGroundControl for it to work %%% + #May need to open QGroundControl for it to work make px4_sitl gazebo -- Create px4 package + +#### 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 @@ -71,39 +79,44 @@ Steps to recreate stable PX4 environment + working repo 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 +## 3) oscillation_ctrl Dependencies +### INSTALL XTERM sudo apt-get update -y sudo apt-get install -y xterm --INSTALL MAVROS_CONTROLLERS + +### 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: - - - - with: - - -- CHANGE DEVEL/SETUP.BASH - In catkin_ws (or any working directory) add to devel/setup.bash: + #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 + copy (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 @@ -113,7 +126,11 @@ Steps to recreate stable PX4 environment + working repo cd $CURRENT_DIR -#JINJA TETHER FILE +## JINJA TETHER FILE +- spiri_with_tether.sdf.jinja can be altered to create desired tether model +- changes nede to be made in px4 directory and will only take effect and +"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)