You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

142 lines
2.5 KiB

px4_add_board(
PLATFORM nuttx
VENDOR px4
MODEL fmu-v5
LABEL ctrlalloc
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m7
ROMFSROOT px4fmu_common
IO px4_io-v2_default
TESTING
UAVCAN_INTERFACES 2
SERIAL_PORTS
GPS1:/dev/ttyS0
TEL1:/dev/ttyS1
TEL2:/dev/ttyS2
TEL4:/dev/ttyS3
DRIVERS
adc/board_adc
adc/ads1115
barometer # all available barometer drivers
batt_smbus
camera_capture
camera_trigger
differential_pressure # all available differential pressure drivers
distance_sensor # all available distance sensor drivers
dshot
gps
#heater
#imu # all available imu drivers
imu/analog_devices/adis16448
imu/adis16477
imu/adis16497
imu/bosch/bmi055
imu/invensense/icm20602
imu/invensense/icm20689
irlock
lights/blinkm
lights/rgbled
lights/rgbled_ncp5623c
lights/rgbled_pwm
magnetometer # all available magnetometer drivers
optical_flow # all available optical flow drivers
#osd
pca9685
pca9685_pwm_out
power_monitor/ina226
#protocol_splitter
pwm_input
pwm_out_sim
pwm_out
px4io
rc_input
roboclaw
rpm
safety_button
telemetry # all available telemetry drivers
test_ppm
tone_alarm
uavcan
MODULES
airspeed_selector
angular_velocity_controller
attitude_estimator_q
battery_status
camera_feedback
commander
control_allocator
dataman
ekf2
esc_battery
events
flight_mode_manager
fw_att_control
fw_pos_control_l1
land_detector
landing_target_estimator
load_mon
local_position_estimator
logger
mavlink
mc_att_control
mc_hover_thrust_estimator
mc_pos_control
mc_rate_control
#micrortps_bridge
navigator
rc_update
rover_pos_control
sensors
sih
temperature_compensation
uuv_att_control
Uuv position control extension (#16688) * Commit for the Integration of a position controller for the a Underwater vehicle. This module is an extension of the uuv_att_control to control an Underwater vehicle to any position, given by the SET_POSITION_TARGET_LOCAL_NED which includes x y z yaw. Since the position control is designed for a 6DOF Robot, the roll and pitch angle are controlled to be 0. Additionally there is a stabilization control, which holds the robot at a defined depth, and not move in any direction. In general the idea is to have this position module to control the position of the uuv. The position module reseives the desired position of the uuv and sends appropriate attitude setpoints to the uuv_attitude_control module. Additionally the mixer file is adapted, to include the 6 different inputs(x y z roll pitch yaw). * Commit for the Integration of a position controller for the a Underwater vehicle. This module is an extension of the uuv_att_control to control an Underwater vehicle to any position, given by the SET_POSITION_TARGET_LOCAL_NED which includes x y z yaw. Since the position control is designed for a 6DOF Robot, the roll and pitch angle are controlled to be 0. Additionally there is a stabilization control, which holds the robot at a defined depth, and not move in any direction. In general the idea is to have this position module to control the position of the uuv. The position module receives the desired position of the uuv and sends appropriate attitude setpoints to the uuv_attitude_control module. Additionally the mixer file is adapted, to include the 6 different inputs(x y z roll pitch yaw). Currently not solved/missing: - Problem with gazebo model(propeller moving chaotically). - Mixer correct gazebo vs real life (has to be tested in the future) - correct integration in uuv.apps (when choose which module) - very basic controller chosen (could be improved a lot in the future) * Remove error caused by unused variables and a different build error * added better description of the parameter. Additionally the group is changed. * added better description of the parameter. Additionally the group is changed. Fixed bug about parameter * Added EOF to the files. * Removed parameter for direct position control for safety reasons. * small bugfix
4 years ago
uuv_pos_control
vmount
vtol_att_control
SYSTEMCMDS
bl_update
dmesg
dumpfile
esc_calib
gpio
hardfault_log
i2cdetect
led_control
mft
mixer
motor_ramp
motor_test
mtd
nshterm
param
perf
pwm
reboot
reflect
sd_bench
system_time
tests # tests and test runner
top
topic_listener
tune_control
uorb
usb_connected
ver
work_queue
EXAMPLES
fake_gps
fake_gyro
fake_magnetometer
fixedwing_control # Tutorial code from https://px4.io/dev/example_fixedwing_control
gyro_fft
hello
hwtest # Hardware test
#matlab_csv_serial
px4_mavlink_debug # Tutorial code from http://dev.px4.io/en/debug/debug_values.html
px4_simple_app # Tutorial code from http://dev.px4.io/en/apps/hello_sky.html
rover_steering_control # Rover example app
uuv_example_app
work_item
)