forked from cesar.alejandro/oscillation_ctrl
Update 'README.md'
This commit is contained in:
parent
ee7ec83869
commit
c98b25cfe3
25
README.md
25
README.md
|
@ -65,10 +65,8 @@ Initilize rosdep:
|
||||||
#### Download QGroundControl from:
|
#### Download QGroundControl from:
|
||||||
https://docs.qgroundcontrol.com/master/en/releases/daily_builds.html
|
https://docs.qgroundcontrol.com/master/en/releases/daily_builds.html
|
||||||
|
|
||||||
#### Build jMAVSim and Gazebo
|
#### Build Gazebo Sim
|
||||||
cd ~/PX4-Autopilot
|
cd ~/PX4-Autopilot
|
||||||
make px4_sitl jmavsim
|
|
||||||
#May need to open QGroundControl for it to work
|
|
||||||
make px4_sitl gazebo
|
make px4_sitl gazebo
|
||||||
|
|
||||||
#### Create px4 package
|
#### Create px4 package
|
||||||
|
@ -96,6 +94,7 @@ Initilize rosdep:
|
||||||
catkin build
|
catkin build
|
||||||
source ~/catkin_ws/devel/setup.bash
|
source ~/catkin_ws/devel/setup.bash
|
||||||
#####Troubleshooting: https://github.com/Jaeyoung-Lim/mavros_controllers
|
#####Troubleshooting: https://github.com/Jaeyoung-Lim/mavros_controllers
|
||||||
|
|
||||||
### TOOLS/SITL_GAZEBO
|
### 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
|
- 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
|
### ROMFS/PX4FMU_COMMON
|
||||||
|
@ -104,16 +103,6 @@ Initilize rosdep:
|
||||||
- add airframe name in _~/PX4-Autopilot/platforms/posix/cmake/sitl_target.cmake_ (no number!)
|
- add airframe name in _~/PX4-Autopilot/platforms/posix/cmake/sitl_target.cmake_ (no number!)
|
||||||
### LAUNCH FILES
|
### LAUNCH FILES
|
||||||
- copy (or add) files from px4_launch directory to '~/PX4-Autopilot/launch'
|
- 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
|
#### 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:
|
||||||
|
@ -148,6 +137,7 @@ In catkin_ws (or any working directory) add to devel/setup.bash:
|
||||||
- __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), 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/path_follow # boolean to run trajectory test
|
/status/path_follow # boolean to run trajectory test
|
||||||
### Subscribes to:
|
### Subscribes to:
|
||||||
none
|
none
|
||||||
|
@ -156,7 +146,8 @@ In catkin_ws (or any working directory) add to devel/setup.bash:
|
||||||
/reference/path # smooth path
|
/reference/path # smooth path
|
||||||
/reference/flatsetpoint # needed to determine thrust
|
/reference/flatsetpoint # needed to determine thrust
|
||||||
### Subscribes to:
|
### Subscribes to:
|
||||||
/status/twoBody_status
|
/status/load_angles
|
||||||
|
/mavros/local_position/pose
|
||||||
/mavros/local_position/velocity_body
|
/mavros/local_position/velocity_body
|
||||||
/mavros/imu/data
|
/mavros/imu/data
|
||||||
/mavros/state
|
/mavros/state
|
||||||
|
@ -164,12 +155,12 @@ In catkin_ws (or any working directory) add to devel/setup.bash:
|
||||||
- __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
|
||||||
/reference/flatsetpoint # needed to determine thrust
|
|
||||||
### Subscribes to:
|
### Subscribes to:
|
||||||
/status/twoBody_status
|
/status/load_angles
|
||||||
/reference/path
|
/reference/path
|
||||||
/mavros/imu/data
|
/mavros/local_position/pose
|
||||||
/mavros/local_position/velocity_body
|
/mavros/local_position/velocity_body
|
||||||
|
/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:
|
||||||
|
|
Loading…
Reference in New Issue