Update 'README.md'

This commit is contained in:
cesar.alejandro 2022-07-05 07:55:28 -07:00
parent 7a84c2ca33
commit b42dba5375
1 changed files with 89 additions and 88 deletions

View File

@ -12,17 +12,17 @@ Steps to recreate stable PX4 environment + working repo
## 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' 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 keys
sudo apt install curl # if you haven't already installed curl 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 - curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | sudo apt-key add -
### INSTALLATION ### Installation
sudo apt update sudo apt update
sudo apt install ros-melodic-desktop-full sudo apt install ros-melodic-desktop-full
### ENVIRONMENT SETUP ### Environment setup
echo "source /opt/ros/melodic/setup.bash" >> ~/.bashrc echo "source /opt/ros/melodic/setup.bash" >> ~/.bashrc
### DEPENDENCIES ### Dependencies
sudo apt install python-rosdep python-rosinstall python-rosinstall-generator python-wstool build-essential sudo apt install python-rosdep python-rosinstall python-rosinstall-generator python-wstool build-essential
Initilize rosdep: Initilize rosdep:
@ -30,35 +30,35 @@ Initilize rosdep:
sudo apt install python-rosdep sudo apt install python-rosdep
sudo rosdep init sudo rosdep init
rosdep update rosdep update
### PX4 DEPENDENCIES ### PX4 Dependencies
sudo apt-get install python-catkin-tools python-rosinstall-generator -y sudo apt-get install python-catkin-tools python-rosinstall-generator -y
wstool init ~/catkin_ws/src wstool init ~/catkin_ws/src
### MAVLINK ### MAVLINK
rosinstall_generator --rosdistro melodic mavlink | tee /tmp/mavros.rosinstall rosinstall_generator --rosdistro melodic mavlink | tee /tmp/mavros.rosinstall
### MAVROS ### MAVROS
rosinstall_generator --upstream mavros | tee -a /tmp/mavros.rosinstall rosinstall_generator --upstream mavros | tee -a /tmp/mavros.rosinstall
### CREATE WORKSPACE AND DEPS ### Create workspace and deps
cd ~/catkin_ws cd ~/catkin_ws
wstool merge -t src /tmp/mavros.rosinstall wstool merge -t src /tmp/mavros.rosinstall
wstool update -t src -j4 wstool update -t src -j4
rosdep install --from-paths src --ignore-src -y rosdep install --from-paths src --ignore-src -y
### INSTALL GEOGRAPHIC LIB DATASETS ### Install geographic datasets
cd ~/catkin_ws cd ~/catkin_ws
sudo ./src/mavros/mavros/scripts/install_geographiclib_datasets.sh sudo ./src/mavros/mavros/scripts/install_geographiclib_datasets.sh
### BUILD SOURCE ### Build source
cd ~/catkin_ws cd ~/catkin_ws
catkin build catkin build
## 2) PX4 Environment Development ## 2) PX4 Environment Development
### DOWNLOAD PX4 SOURCE CODE ### Download PX4 source code
git clone https://github.com/PX4/PX4-Autopilot.git --recursive git clone https://github.com/PX4/PX4-Autopilot.git --recursive
### RUN UBUNTU.SH ### Run ubuntu.sh
bash ./PX4-Autopilot/Tools/setup/ubuntu.sh bash ./PX4-Autopilot/Tools/setup/ubuntu.sh
#Restart computer after it is done #Restart computer after it is done
### BUILD ROS/GAZEBO: Gets Gazebo9 ### Build ROS and Gazebo - This defaults to Gazebo9
wget https://raw.githubusercontent.com/PX4/Devguide/master/build_scripts/ubuntu_sim_ros_melodic.sh wget https://raw.githubusercontent.com/PX4/Devguide/master/build_scripts/ubuntu_sim_ros_melodic.sh
bash ubuntu_sim_ros_melodic.sh bash ubuntu_sim_ros_melodic.sh
@ -77,39 +77,36 @@ Initilize rosdep:
export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:$(pwd)/Tools/sitl_gazebo export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:$(pwd)/Tools/sitl_gazebo
roslaunch px4 posix_sitl.launch roslaunch px4 posix_sitl.launch
## 3) oscillation_ctrl Dependencies ## 3) Set up oscillation_ctrl
### INSTALL XTERM ### Install xterm
sudo apt-get update -y sudo apt-get update -y
sudo apt-get install -y xterm sudo apt-get install -y xterm
### INSTALL MAVROS_CONTROLLERS ### Clone oscillation_ctrl
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
### CLONE OSCILLATION_CTRL
cd ~catkin_ws/src cd ~catkin_ws/src
git clone https://git.spirirobotics.com/cesar.alejandro/oscillation_ctrl.git git clone https://git.spirirobotics.com/cesar.alejandro/oscillation_ctrl.git
### 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 ### 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/models/* ~/PX4-Autopilot/Tools/sitl_gazebo/models
cp -R ~catkin_ws/src/oscillation_ctrl/worlds/* ~/PX4-Autopilot/Tools/sitl_gazebo/worlds cp -R ~catkin_ws/src/oscillation_ctrl/worlds/* ~/PX4-Autopilot/Tools/sitl_gazebo/worlds
### ROMFS/PX4FMU_COMMON
- copy (or add) files in _oscillation_ctrl/airframes_ to _PX4-Autopilot/ROMFS/px4fmu_common/init.d-posix/airframes_ ### 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/* 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 model names to _CmakeLists.txt_ in same 'airframe' folder (with number... 4000_spiri and 4001_spiri_with_tether)
### LAUNCH FILES
- copy (or add) files from px4_launch directory to '~/PX4-Autopilot/launch' 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 cp -R ~catkin_ws/src/oscillation_ctrl/px4_launch/* ~/PX4-Autopilot/launch
#### CHANGE DEVEL/SETUP.BASH #### Change devel/setup.bash
In catkin_ws (or any working directory) add to devel/setup.bash: In catkin_ws (or any working directory) add to devel/setup.bash:
CURRENT_DIR=$(pwd) CURRENT_DIR=$(pwd)
@ -129,6 +126,7 @@ In catkin_ws (or any working directory) add to devel/setup.bash:
- tl: segment length (should be no shorter than 0.3 meters) - 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_ (Ln 288 - may change in future) in the _~/PX4-Autopilot/Tools/sitl_gazebo_ folder: - __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:
COMMAND COMMAND
${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py models/spiri_with_tether/spiri_with_tether.sdf} ${CMAKE_CURRENT_SOURCE_DIR} ${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 DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/scripts/jinja_gen.py models/spiri_with_tether/spiri_with_tether.sdf
@ -138,14 +136,19 @@ In catkin_ws (or any working directory) add to devel/setup.bash:
## ROS NODES ## ROS NODES
- __LinkState.py__ determines payload load angles and their rates (theta and phi), as well as determines tether length and keeps track of variables needed in case of step test. __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: ### Publishes to:
/status/twoBody_status # localization and angles /status/twoBody_status # localization and angles
/status/load_angles # payload angles (and tates) relative to vehicle /status/load_angles # payload angles (and tates) relative to vehicle
/status/path_follow # boolean to run trajectory test /status/path_follow # boolean to run trajectory test
### Subscribes to: ### Subscribes to:
none none
- __ref_signalGen.py__ takes in desired position (xd) and determines smooth path trajectory. __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:
none
### Subscribes to:
/reference/waypoints
__ref_signalGen.py__ takes in desired position (xd) and determines smooth path trajectory.
### Publishes to: ### Publishes to:
/reference/path # smooth path /reference/path # smooth path
/reference/flatsetpoint # needed to determine thrust /reference/flatsetpoint # needed to determine thrust
@ -156,7 +159,7 @@ In catkin_ws (or any working directory) add to devel/setup.bash:
/mavros/imu/data /mavros/imu/data
/mavros/state /mavros/state
/reference/waypoints /reference/waypoints
- __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. __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: ### Publishes to:
/command/quaternions # attitude commands /command/quaternions # attitude commands
### Subscribes to: ### Subscribes to:
@ -166,7 +169,7 @@ In catkin_ws (or any working directory) add to devel/setup.bash:
/mavros/local_position/velocity_body /mavros/local_position/velocity_body
/mavros/imu/data /mavros/imu/data
- node from _mavros_controllers/geometric_controller_ subscribes to _/reference/flatsetpoint_ to determine thrust commands which are published to _command/bodyrate_command_ by default - node from _mavros_controllers/geometric_controller_ subscribes to _/reference/flatsetpoint_ to determine thrust commands which are published to _command/bodyrate_command_ by default
- __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. __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: ### Publishes to:
mavros/setpoint_position/local # needed to hover @ set height mavros/setpoint_position/local # needed to hover @ set height
mavros/setpoint_raw/attitude # attitude and thrust commands mavros/setpoint_raw/attitude # attitude and thrust commands
@ -183,17 +186,15 @@ In catkin_ws (or any working directory) add to devel/setup.bash:
__model:__ __model:__
spiri_with_tether # default spiri_with_tether # Spiri Mu with a tethered payload
spiri spiri # Spiri Mu without tethered paylaod
headless_spiri_with_tether # headless mode: launches with no Gazebo GUI headless_spiri_with_tether # headless mode: launches with no Gazebo GUI. This is the default model
__test:__ __test:__
none # default none # default
step # step input - default is 5 m step # step input - default is 5 m
square # square trajectory square # square trajectory
- To run the simulation with a tethered payload headless mode and perform a step test: To run the simulation with a tethered payload headless mode and perform a step test:
roslaunch oscillation_ctrl klausen_dampen.launch model:=headless_spiri_with_tether test:=step
roslaunch oscillation_ctrl oscillation_damp.launch model:=headless_spiri_with_tether test:=step