forked from xtdrone/XTDrone
add px4 config
This commit is contained in:
parent
23f966dab1
commit
64b3f2da6f
|
@ -107,4 +107,4 @@ Xiao, K., Ma, L., Tan, S., Cong, Y., Wang, X.: Implementation of UAV Coordinatio
|
|||
|
||||
非常感谢你们对XTDrone团队的支持
|
||||
|
||||
高多多
|
||||
高多多 李照祥
|
||||
|
|
|
@ -191,25 +191,25 @@ Visualization Manager:
|
|||
Views:
|
||||
Current:
|
||||
Class: rviz/Orbit
|
||||
Distance: 10.266495704650879
|
||||
Distance: 14.177528381347656
|
||||
Enable Stereo Rendering:
|
||||
Stereo Eye Separation: 0.05999999865889549
|
||||
Stereo Focal Distance: 1
|
||||
Swap Stereo Eyes: false
|
||||
Value: false
|
||||
Focal Point:
|
||||
X: -0.0488688126206398
|
||||
Y: -1.6133887767791748
|
||||
Z: 2.466456890106201
|
||||
X: -1.4988659620285034
|
||||
Y: -2.914069652557373
|
||||
Z: 3.321497678756714
|
||||
Focal Shape Fixed Size: true
|
||||
Focal Shape Size: 0.05000000074505806
|
||||
Invert Z Axis: false
|
||||
Name: Current View
|
||||
Near Clip Distance: 0.009999999776482582
|
||||
Pitch: 0.5503982305526733
|
||||
Pitch: 0.32539814710617065
|
||||
Target Frame: <Fixed Frame>
|
||||
Value: Orbit (rviz)
|
||||
Yaw: 1.8953969478607178
|
||||
Yaw: 1.8703962564468384
|
||||
Saved: ~
|
||||
Window Geometry:
|
||||
Displays:
|
||||
|
@ -219,7 +219,7 @@ Window Geometry:
|
|||
Hide Right Dock: true
|
||||
Image:
|
||||
collapsed: false
|
||||
QMainWindow State: 000000ff00000000fd00000004000000000000037200000363fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000000ee000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000001310000026f0000001600ffffff000000010000010000000363fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000363000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000039f0000003efc0100000002fb0000000800540069006d006501000000000000039f000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000000270000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
QMainWindow State: 000000ff00000000fd00000004000000000000037200000363fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000000ee000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d00610067006501000001310000026f0000001600ffffff000000010000010000000363fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000363000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073d0000003efc0100000002fb0000000800540069006d006501000000000000073d000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000003c50000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
|
||||
Selection:
|
||||
collapsed: false
|
||||
Time:
|
||||
|
@ -228,6 +228,6 @@ Window Geometry:
|
|||
collapsed: false
|
||||
Views:
|
||||
collapsed: true
|
||||
Width: 927
|
||||
X: 993
|
||||
Width: 1853
|
||||
X: 67
|
||||
Y: 27
|
||||
|
|
Binary file not shown.
After Width: | Height: | Size: 1.1 MiB |
Binary file not shown.
|
@ -1,18 +0,0 @@
|
|||
<?xml version="1.0"?>
|
||||
<launch>
|
||||
<!-- Posix SITL PX4 launch script -->
|
||||
<!-- Launches Only PX4 SITL. This can be used by external projects -->
|
||||
|
||||
<!-- PX4 config arguments -->
|
||||
<arg name="est" default="ekf2"/>
|
||||
<arg name="vehicle" default="iris"/>
|
||||
<arg name="ID" default="0"/>
|
||||
<arg name="interactive" default="true"/>
|
||||
|
||||
<env name="PX4_SIM_MODEL" value="$(arg vehicle)" />
|
||||
<env name="PX4_ESTIMATOR" value="$(arg est)" />
|
||||
<arg unless="$(arg interactive)" name="px4_command_arg1" value=""/>
|
||||
<arg if="$(arg interactive)" name="px4_command_arg1" value="-d"/>
|
||||
<node name="sitl_$(arg ID)" pkg="px4" type="px4" output="screen" args="$(find px4)/ROMFS/px4fmu_common -s etc/init.d-posix/rcS -i $(arg ID) $(arg px4_command_arg1)">
|
||||
</node>
|
||||
</launch>
|
|
@ -0,0 +1,26 @@
|
|||
<launch>
|
||||
<!-- vim: set ft=xml noet : -->
|
||||
<!-- example launch script for PX4 based FCU's -->
|
||||
|
||||
<arg name="fcu_url" default="/dev/ttyACM0:57600" />
|
||||
<arg name="gcs_url" default="" />
|
||||
<arg name="tgt_system" default="1" />
|
||||
<arg name="tgt_component" default="1" />
|
||||
<arg name="log_output" default="screen" />
|
||||
<arg name="fcu_protocol" default="v2.0" />
|
||||
<arg name="respawn_mavros" default="false" />
|
||||
<arg name="config_yaml" default="$(find mavros)/launch/px4_config.yaml" />
|
||||
|
||||
<include file="$(find mavros)/launch/node.launch">
|
||||
<arg name="pluginlists_yaml" value="$(find mavros)/launch/px4_pluginlists.yaml" />
|
||||
<arg name="config_yaml" value="$(arg config_yaml)" />
|
||||
|
||||
<arg name="fcu_url" value="$(arg fcu_url)" />
|
||||
<arg name="gcs_url" value="$(arg gcs_url)" />
|
||||
<arg name="tgt_system" value="$(arg tgt_system)" />
|
||||
<arg name="tgt_component" value="$(arg tgt_component)" />
|
||||
<arg name="log_output" value="$(arg log_output)" />
|
||||
<arg name="fcu_protocol" value="$(arg fcu_protocol)" />
|
||||
<arg name="respawn_mavros" default="$(arg respawn_mavros)" />
|
||||
</include>
|
||||
</launch>
|
|
@ -0,0 +1,262 @@
|
|||
# Common configuration for PX4 autopilot
|
||||
#
|
||||
# node:
|
||||
startup_px4_usb_quirk: true
|
||||
|
||||
# --- system plugins ---
|
||||
|
||||
# sys_status & sys_time connection options
|
||||
conn:
|
||||
heartbeat_rate: 1.0 # send hertbeat rate in Hertz
|
||||
timeout: 10.0 # hertbeat timeout in seconds
|
||||
timesync_rate: 10.0 # TIMESYNC rate in Hertz (feature disabled if 0.0)
|
||||
system_time_rate: 1.0 # send system time to FCU rate in Hertz (disabled if 0.0)
|
||||
|
||||
# sys_status
|
||||
sys:
|
||||
min_voltage: 10.0 # diagnostics min voltage
|
||||
disable_diag: false # disable all sys_status diagnostics, except heartbeat
|
||||
|
||||
# sys_time
|
||||
time:
|
||||
time_ref_source: "fcu" # time_reference source
|
||||
timesync_mode: MAVLINK
|
||||
timesync_avg_alpha: 0.6 # timesync averaging factor
|
||||
|
||||
# --- mavros plugins (alphabetical order) ---
|
||||
|
||||
# 3dr_radio
|
||||
tdr_radio:
|
||||
low_rssi: 40 # raw rssi lower level for diagnostics
|
||||
|
||||
# actuator_control
|
||||
# None
|
||||
|
||||
# command
|
||||
cmd:
|
||||
use_comp_id_system_control: false # quirk for some old FCUs
|
||||
|
||||
# dummy
|
||||
# None
|
||||
|
||||
# ftp
|
||||
# None
|
||||
|
||||
# global_position
|
||||
global_position:
|
||||
frame_id: "map" # origin frame
|
||||
child_frame_id: "iris_0/base_link" # body-fixed frame
|
||||
rot_covariance: 99999.0 # covariance for attitude?
|
||||
gps_uere: 1.0 # User Equivalent Range Error (UERE) of GPS sensor (m)
|
||||
use_relative_alt: true # use relative altitude for local coordinates
|
||||
tf:
|
||||
send: false # send TF?
|
||||
frame_id: "map" # TF frame_id
|
||||
global_frame_id: "earth" # TF earth frame_id
|
||||
child_frame_id: "iris_0/base_link" # TF child_frame_id
|
||||
|
||||
# imu_pub
|
||||
imu:
|
||||
frame_id: "iris_0/base_link"
|
||||
# need find actual values
|
||||
linear_acceleration_stdev: 0.0003
|
||||
angular_velocity_stdev: 0.0003490659 // 0.02 degrees
|
||||
orientation_stdev: 1.0
|
||||
magnetic_stdev: 0.0
|
||||
|
||||
# local_position
|
||||
local_position:
|
||||
frame_id: "map"
|
||||
tf:
|
||||
send: true
|
||||
frame_id: "map"
|
||||
child_frame_id: "iris_0/base_link"
|
||||
send_fcu: false
|
||||
|
||||
# param
|
||||
# None, used for FCU params
|
||||
|
||||
# rc_io
|
||||
# None
|
||||
|
||||
# safety_area
|
||||
safety_area:
|
||||
p1: {x: 1.0, y: 1.0, z: 1.0}
|
||||
p2: {x: -1.0, y: -1.0, z: -1.0}
|
||||
|
||||
# setpoint_accel
|
||||
setpoint_accel:
|
||||
send_force: false
|
||||
|
||||
# setpoint_attitude
|
||||
setpoint_attitude:
|
||||
reverse_thrust: false # allow reversed thrust
|
||||
use_quaternion: false # enable PoseStamped topic subscriber
|
||||
tf:
|
||||
listen: false # enable tf listener (disable topic subscribers)
|
||||
frame_id: "map"
|
||||
child_frame_id: "target_attitude"
|
||||
rate_limit: 50.0
|
||||
|
||||
setpoint_raw:
|
||||
thrust_scaling: 1.0 # used in setpoint_raw attitude callback.
|
||||
# Note: PX4 expects normalized thrust values between 0 and 1, which means that
|
||||
# the scaling needs to be unitary and the inputs should be 0..1 as well.
|
||||
|
||||
# setpoint_position
|
||||
setpoint_position:
|
||||
tf:
|
||||
listen: false # enable tf listener (disable topic subscribers)
|
||||
frame_id: "map"
|
||||
child_frame_id: "target_position"
|
||||
rate_limit: 50.0
|
||||
mav_frame: LOCAL_NED
|
||||
|
||||
# setpoint_velocity
|
||||
setpoint_velocity:
|
||||
mav_frame: LOCAL_NED
|
||||
|
||||
# vfr_hud
|
||||
# None
|
||||
|
||||
# waypoint
|
||||
mission:
|
||||
pull_after_gcs: true # update mission if gcs updates
|
||||
use_mission_item_int: true # use the MISSION_ITEM_INT message instead of MISSION_ITEM
|
||||
# for uploading waypoints to FCU
|
||||
|
||||
# --- mavros extras plugins (same order) ---
|
||||
|
||||
# adsb
|
||||
# None
|
||||
|
||||
# debug_value
|
||||
# None
|
||||
|
||||
# distance_sensor
|
||||
## Currently available orientations:
|
||||
# Check http://wiki.ros.org/mavros/Enumerations
|
||||
##
|
||||
distance_sensor:
|
||||
hrlv_ez4_pub:
|
||||
id: 0
|
||||
frame_id: "hrlv_ez4_sonar"
|
||||
orientation: PITCH_270 # RPY:{0.0, 270.0, 0.0} - downward-facing
|
||||
field_of_view: 0.0 # XXX TODO
|
||||
send_tf: true
|
||||
sensor_position: {x: 0.0, y: 0.0, z: -0.1}
|
||||
lidarlite_pub:
|
||||
id: 1
|
||||
frame_id: "lidarlite_laser"
|
||||
orientation: PITCH_270
|
||||
field_of_view: 0.0 # XXX TODO
|
||||
send_tf: true
|
||||
sensor_position: {x: 0.0, y: 0.0, z: -0.1}
|
||||
sonar_1_sub:
|
||||
subscriber: true
|
||||
id: 2
|
||||
orientation: PITCH_270
|
||||
laser_1_sub:
|
||||
subscriber: true
|
||||
id: 3
|
||||
orientation: PITCH_270
|
||||
|
||||
# image_pub
|
||||
image:
|
||||
frame_id: "px4flow"
|
||||
|
||||
# fake_gps
|
||||
fake_gps:
|
||||
# select data source
|
||||
use_mocap: true # ~mocap/pose
|
||||
mocap_transform: true # ~mocap/tf instead of pose
|
||||
use_vision: false # ~vision (pose)
|
||||
# origin (default: Zürich)
|
||||
geo_origin:
|
||||
lat: 47.3667 # latitude [degrees]
|
||||
lon: 8.5500 # longitude [degrees]
|
||||
alt: 408.0 # altitude (height over the WGS-84 ellipsoid) [meters]
|
||||
eph: 2.0
|
||||
epv: 2.0
|
||||
satellites_visible: 5 # virtual number of visible satellites
|
||||
fix_type: 3 # type of GPS fix (default: 3D)
|
||||
tf:
|
||||
listen: false
|
||||
send: false # send TF?
|
||||
frame_id: "map" # TF frame_id
|
||||
child_frame_id: "fix" # TF child_frame_id
|
||||
rate_limit: 10.0 # TF rate
|
||||
gps_rate: 5.0 # GPS data publishing rate
|
||||
|
||||
# landing_target
|
||||
landing_target:
|
||||
listen_lt: false
|
||||
mav_frame: "LOCAL_NED"
|
||||
land_target_type: "VISION_FIDUCIAL"
|
||||
image:
|
||||
width: 640 # [pixels]
|
||||
height: 480
|
||||
camera:
|
||||
fov_x: 2.0071286398 # default: 115 [degrees]
|
||||
fov_y: 2.0071286398
|
||||
tf:
|
||||
send: true
|
||||
listen: false
|
||||
frame_id: "landing_target"
|
||||
child_frame_id: "camera_center"
|
||||
rate_limit: 10.0
|
||||
target_size: {x: 0.3, y: 0.3}
|
||||
|
||||
# mocap_pose_estimate
|
||||
mocap:
|
||||
# select mocap source
|
||||
use_tf: false # ~mocap/tf
|
||||
use_pose: true # ~mocap/pose
|
||||
|
||||
# odom
|
||||
odometry:
|
||||
fcu:
|
||||
odom_parent_id_des: "map" # desired parent frame rotation of the FCU's odometry
|
||||
odom_child_id_des: "iris_0/base_link" # desired child frame rotation of the FCU's odometry
|
||||
|
||||
# px4flow
|
||||
px4flow:
|
||||
frame_id: "px4flow"
|
||||
ranger_fov: 0.118682 # 6.8 degrees at 5 meters, 31 degrees at 1 meter
|
||||
ranger_min_range: 0.3 # meters
|
||||
ranger_max_range: 5.0 # meters
|
||||
|
||||
# vision_pose_estimate
|
||||
vision_pose:
|
||||
tf:
|
||||
listen: false # enable tf listener (disable topic subscribers)
|
||||
frame_id: "odom"
|
||||
child_frame_id: "vision_estimate"
|
||||
rate_limit: 10.0
|
||||
|
||||
# vision_speed_estimate
|
||||
vision_speed:
|
||||
listen_twist: true # enable listen to twist topic, else listen to vec3d topic
|
||||
twist_cov: true # enable listen to twist with covariance topic
|
||||
|
||||
# vibration
|
||||
vibration:
|
||||
frame_id: "iris_0/base_link"
|
||||
|
||||
# wheel_odometry
|
||||
wheel_odometry:
|
||||
count: 2 # number of wheels to compute odometry
|
||||
use_rpm: false # use wheel's RPM instead of cumulative distance to compute odometry
|
||||
wheel0: {x: 0.0, y: -0.15, radius: 0.05} # x-, y-offset (m,NED) and radius (m)
|
||||
wheel1: {x: 0.0, y: 0.15, radius: 0.05} # x-, y-offset (m,NED) and radius (m)
|
||||
send_raw: true # send wheel's RPM and cumulative distance (~/wheel_odometry/rpm, ~/wheel_odometry/distance)
|
||||
send_twist: false # send geometry_msgs/TwistWithCovarianceStamped instead of nav_msgs/Odometry
|
||||
frame_id: "odom" # origin frame
|
||||
child_frame_id: "iris_0/base_link" # body-fixed frame
|
||||
vel_error: 0.1 # wheel velocity measurement error 1-std (m/s)
|
||||
tf:
|
||||
send: false
|
||||
frame_id: "odom"
|
||||
child_frame_id: "iris_0/base_link"
|
||||
|
||||
# vim:set ts=2 sw=2 et:
|
|
@ -0,0 +1,262 @@
|
|||
# Common configuration for PX4 autopilot
|
||||
#
|
||||
# node:
|
||||
startup_px4_usb_quirk: true
|
||||
|
||||
# --- system plugins ---
|
||||
|
||||
# sys_status & sys_time connection options
|
||||
conn:
|
||||
heartbeat_rate: 1.0 # send hertbeat rate in Hertz
|
||||
timeout: 10.0 # hertbeat timeout in seconds
|
||||
timesync_rate: 10.0 # TIMESYNC rate in Hertz (feature disabled if 0.0)
|
||||
system_time_rate: 1.0 # send system time to FCU rate in Hertz (disabled if 0.0)
|
||||
|
||||
# sys_status
|
||||
sys:
|
||||
min_voltage: 10.0 # diagnostics min voltage
|
||||
disable_diag: false # disable all sys_status diagnostics, except heartbeat
|
||||
|
||||
# sys_time
|
||||
time:
|
||||
time_ref_source: "fcu" # time_reference source
|
||||
timesync_mode: MAVLINK
|
||||
timesync_avg_alpha: 0.6 # timesync averaging factor
|
||||
|
||||
# --- mavros plugins (alphabetical order) ---
|
||||
|
||||
# 3dr_radio
|
||||
tdr_radio:
|
||||
low_rssi: 40 # raw rssi lower level for diagnostics
|
||||
|
||||
# actuator_control
|
||||
# None
|
||||
|
||||
# command
|
||||
cmd:
|
||||
use_comp_id_system_control: false # quirk for some old FCUs
|
||||
|
||||
# dummy
|
||||
# None
|
||||
|
||||
# ftp
|
||||
# None
|
||||
|
||||
# global_position
|
||||
global_position:
|
||||
frame_id: "map" # origin frame
|
||||
child_frame_id: "iris_1/base_link" # body-fixed frame
|
||||
rot_covariance: 99999.0 # covariance for attitude?
|
||||
gps_uere: 1.0 # User Equivalent Range Error (UERE) of GPS sensor (m)
|
||||
use_relative_alt: true # use relative altitude for local coordinates
|
||||
tf:
|
||||
send: false # send TF?
|
||||
frame_id: "map" # TF frame_id
|
||||
global_frame_id: "earth" # TF earth frame_id
|
||||
child_frame_id: "iris_1/base_link" # TF child_frame_id
|
||||
|
||||
# imu_pub
|
||||
imu:
|
||||
frame_id: "iris_1/base_link"
|
||||
# need find actual values
|
||||
linear_acceleration_stdev: 0.0003
|
||||
angular_velocity_stdev: 0.0003490659 // 0.02 degrees
|
||||
orientation_stdev: 1.0
|
||||
magnetic_stdev: 0.0
|
||||
|
||||
# local_position
|
||||
local_position:
|
||||
frame_id: "map"
|
||||
tf:
|
||||
send: true
|
||||
frame_id: "map"
|
||||
child_frame_id: "iris_1/base_link"
|
||||
send_fcu: false
|
||||
|
||||
# param
|
||||
# None, used for FCU params
|
||||
|
||||
# rc_io
|
||||
# None
|
||||
|
||||
# safety_area
|
||||
safety_area:
|
||||
p1: {x: 1.0, y: 1.0, z: 1.0}
|
||||
p2: {x: -1.0, y: -1.0, z: -1.0}
|
||||
|
||||
# setpoint_accel
|
||||
setpoint_accel:
|
||||
send_force: false
|
||||
|
||||
# setpoint_attitude
|
||||
setpoint_attitude:
|
||||
reverse_thrust: false # allow reversed thrust
|
||||
use_quaternion: false # enable PoseStamped topic subscriber
|
||||
tf:
|
||||
listen: false # enable tf listener (disable topic subscribers)
|
||||
frame_id: "map"
|
||||
child_frame_id: "target_attitude"
|
||||
rate_limit: 50.0
|
||||
|
||||
setpoint_raw:
|
||||
thrust_scaling: 1.0 # used in setpoint_raw attitude callback.
|
||||
# Note: PX4 expects normalized thrust values between 0 and 1, which means that
|
||||
# the scaling needs to be unitary and the inputs should be 0..1 as well.
|
||||
|
||||
# setpoint_position
|
||||
setpoint_position:
|
||||
tf:
|
||||
listen: false # enable tf listener (disable topic subscribers)
|
||||
frame_id: "map"
|
||||
child_frame_id: "target_position"
|
||||
rate_limit: 50.0
|
||||
mav_frame: LOCAL_NED
|
||||
|
||||
# setpoint_velocity
|
||||
setpoint_velocity:
|
||||
mav_frame: LOCAL_NED
|
||||
|
||||
# vfr_hud
|
||||
# None
|
||||
|
||||
# waypoint
|
||||
mission:
|
||||
pull_after_gcs: true # update mission if gcs updates
|
||||
use_mission_item_int: true # use the MISSION_ITEM_INT message instead of MISSION_ITEM
|
||||
# for uploading waypoints to FCU
|
||||
|
||||
# --- mavros extras plugins (same order) ---
|
||||
|
||||
# adsb
|
||||
# None
|
||||
|
||||
# debug_value
|
||||
# None
|
||||
|
||||
# distance_sensor
|
||||
## Currently available orientations:
|
||||
# Check http://wiki.ros.org/mavros/Enumerations
|
||||
##
|
||||
distance_sensor:
|
||||
hrlv_ez4_pub:
|
||||
id: 0
|
||||
frame_id: "hrlv_ez4_sonar"
|
||||
orientation: PITCH_270 # RPY:{0.0, 270.0, 0.0} - downward-facing
|
||||
field_of_view: 0.0 # XXX TODO
|
||||
send_tf: true
|
||||
sensor_position: {x: 0.0, y: 0.0, z: -0.1}
|
||||
lidarlite_pub:
|
||||
id: 1
|
||||
frame_id: "lidarlite_laser"
|
||||
orientation: PITCH_270
|
||||
field_of_view: 0.0 # XXX TODO
|
||||
send_tf: true
|
||||
sensor_position: {x: 0.0, y: 0.0, z: -0.1}
|
||||
sonar_1_sub:
|
||||
subscriber: true
|
||||
id: 2
|
||||
orientation: PITCH_270
|
||||
laser_1_sub:
|
||||
subscriber: true
|
||||
id: 3
|
||||
orientation: PITCH_270
|
||||
|
||||
# image_pub
|
||||
image:
|
||||
frame_id: "px4flow"
|
||||
|
||||
# fake_gps
|
||||
fake_gps:
|
||||
# select data source
|
||||
use_mocap: true # ~mocap/pose
|
||||
mocap_transform: true # ~mocap/tf instead of pose
|
||||
use_vision: false # ~vision (pose)
|
||||
# origin (default: Zürich)
|
||||
geo_origin:
|
||||
lat: 47.3667 # latitude [degrees]
|
||||
lon: 8.5500 # longitude [degrees]
|
||||
alt: 408.0 # altitude (height over the WGS-84 ellipsoid) [meters]
|
||||
eph: 2.0
|
||||
epv: 2.0
|
||||
satellites_visible: 5 # virtual number of visible satellites
|
||||
fix_type: 3 # type of GPS fix (default: 3D)
|
||||
tf:
|
||||
listen: false
|
||||
send: false # send TF?
|
||||
frame_id: "map" # TF frame_id
|
||||
child_frame_id: "fix" # TF child_frame_id
|
||||
rate_limit: 10.0 # TF rate
|
||||
gps_rate: 5.0 # GPS data publishing rate
|
||||
|
||||
# landing_target
|
||||
landing_target:
|
||||
listen_lt: false
|
||||
mav_frame: "LOCAL_NED"
|
||||
land_target_type: "VISION_FIDUCIAL"
|
||||
image:
|
||||
width: 640 # [pixels]
|
||||
height: 480
|
||||
camera:
|
||||
fov_x: 2.0071286398 # default: 115 [degrees]
|
||||
fov_y: 2.0071286398
|
||||
tf:
|
||||
send: true
|
||||
listen: false
|
||||
frame_id: "landing_target"
|
||||
child_frame_id: "camera_center"
|
||||
rate_limit: 10.0
|
||||
target_size: {x: 0.3, y: 0.3}
|
||||
|
||||
# mocap_pose_estimate
|
||||
mocap:
|
||||
# select mocap source
|
||||
use_tf: false # ~mocap/tf
|
||||
use_pose: true # ~mocap/pose
|
||||
|
||||
# odom
|
||||
odometry:
|
||||
fcu:
|
||||
odom_parent_id_des: "map" # desired parent frame rotation of the FCU's odometry
|
||||
odom_child_id_des: "iris_1/base_link" # desired child frame rotation of the FCU's odometry
|
||||
|
||||
# px4flow
|
||||
px4flow:
|
||||
frame_id: "px4flow"
|
||||
ranger_fov: 0.118682 # 6.8 degrees at 5 meters, 31 degrees at 1 meter
|
||||
ranger_min_range: 0.3 # meters
|
||||
ranger_max_range: 5.0 # meters
|
||||
|
||||
# vision_pose_estimate
|
||||
vision_pose:
|
||||
tf:
|
||||
listen: false # enable tf listener (disable topic subscribers)
|
||||
frame_id: "odom"
|
||||
child_frame_id: "vision_estimate"
|
||||
rate_limit: 10.0
|
||||
|
||||
# vision_speed_estimate
|
||||
vision_speed:
|
||||
listen_twist: true # enable listen to twist topic, else listen to vec3d topic
|
||||
twist_cov: true # enable listen to twist with covariance topic
|
||||
|
||||
# vibration
|
||||
vibration:
|
||||
frame_id: "iris_1/base_link"
|
||||
|
||||
# wheel_odometry
|
||||
wheel_odometry:
|
||||
count: 2 # number of wheels to compute odometry
|
||||
use_rpm: false # use wheel's RPM instead of cumulative distance to compute odometry
|
||||
wheel0: {x: 0.0, y: -0.15, radius: 0.05} # x-, y-offset (m,NED) and radius (m)
|
||||
wheel1: {x: 0.0, y: 0.15, radius: 0.05} # x-, y-offset (m,NED) and radius (m)
|
||||
send_raw: true # send wheel's RPM and cumulative distance (~/wheel_odometry/rpm, ~/wheel_odometry/distance)
|
||||
send_twist: false # send geometry_msgs/TwistWithCovarianceStamped instead of nav_msgs/Odometry
|
||||
frame_id: "odom" # origin frame
|
||||
child_frame_id: "iris_1/base_link" # body-fixed frame
|
||||
vel_error: 0.1 # wheel velocity measurement error 1-std (m/s)
|
||||
tf:
|
||||
send: false
|
||||
frame_id: "odom"
|
||||
child_frame_id: "iris_1/base_link"
|
||||
|
||||
# vim:set ts=2 sw=2 et:
|
|
@ -0,0 +1,262 @@
|
|||
# Common configuration for PX4 autopilot
|
||||
#
|
||||
# node:
|
||||
startup_px4_usb_quirk: true
|
||||
|
||||
# --- system plugins ---
|
||||
|
||||
# sys_status & sys_time connection options
|
||||
conn:
|
||||
heartbeat_rate: 1.0 # send hertbeat rate in Hertz
|
||||
timeout: 10.0 # hertbeat timeout in seconds
|
||||
timesync_rate: 10.0 # TIMESYNC rate in Hertz (feature disabled if 0.0)
|
||||
system_time_rate: 1.0 # send system time to FCU rate in Hertz (disabled if 0.0)
|
||||
|
||||
# sys_status
|
||||
sys:
|
||||
min_voltage: 10.0 # diagnostics min voltage
|
||||
disable_diag: false # disable all sys_status diagnostics, except heartbeat
|
||||
|
||||
# sys_time
|
||||
time:
|
||||
time_ref_source: "fcu" # time_reference source
|
||||
timesync_mode: MAVLINK
|
||||
timesync_avg_alpha: 0.6 # timesync averaging factor
|
||||
|
||||
# --- mavros plugins (alphabetical order) ---
|
||||
|
||||
# 3dr_radio
|
||||
tdr_radio:
|
||||
low_rssi: 40 # raw rssi lower level for diagnostics
|
||||
|
||||
# actuator_control
|
||||
# None
|
||||
|
||||
# command
|
||||
cmd:
|
||||
use_comp_id_system_control: false # quirk for some old FCUs
|
||||
|
||||
# dummy
|
||||
# None
|
||||
|
||||
# ftp
|
||||
# None
|
||||
|
||||
# global_position
|
||||
global_position:
|
||||
frame_id: "map" # origin frame
|
||||
child_frame_id: "iris_2/base_link" # body-fixed frame
|
||||
rot_covariance: 99999.0 # covariance for attitude?
|
||||
gps_uere: 1.0 # User Equivalent Range Error (UERE) of GPS sensor (m)
|
||||
use_relative_alt: true # use relative altitude for local coordinates
|
||||
tf:
|
||||
send: false # send TF?
|
||||
frame_id: "map" # TF frame_id
|
||||
global_frame_id: "earth" # TF earth frame_id
|
||||
child_frame_id: "iris_2/base_link" # TF child_frame_id
|
||||
|
||||
# imu_pub
|
||||
imu:
|
||||
frame_id: "iris_2/base_link"
|
||||
# need find actual values
|
||||
linear_acceleration_stdev: 0.0003
|
||||
angular_velocity_stdev: 0.0003490659 // 0.02 degrees
|
||||
orientation_stdev: 1.0
|
||||
magnetic_stdev: 0.0
|
||||
|
||||
# local_position
|
||||
local_position:
|
||||
frame_id: "map"
|
||||
tf:
|
||||
send: true
|
||||
frame_id: "map"
|
||||
child_frame_id: "iris_2/base_link"
|
||||
send_fcu: false
|
||||
|
||||
# param
|
||||
# None, used for FCU params
|
||||
|
||||
# rc_io
|
||||
# None
|
||||
|
||||
# safety_area
|
||||
safety_area:
|
||||
p1: {x: 1.0, y: 1.0, z: 1.0}
|
||||
p2: {x: -1.0, y: -1.0, z: -1.0}
|
||||
|
||||
# setpoint_accel
|
||||
setpoint_accel:
|
||||
send_force: false
|
||||
|
||||
# setpoint_attitude
|
||||
setpoint_attitude:
|
||||
reverse_thrust: false # allow reversed thrust
|
||||
use_quaternion: false # enable PoseStamped topic subscriber
|
||||
tf:
|
||||
listen: false # enable tf listener (disable topic subscribers)
|
||||
frame_id: "map"
|
||||
child_frame_id: "target_attitude"
|
||||
rate_limit: 50.0
|
||||
|
||||
setpoint_raw:
|
||||
thrust_scaling: 1.0 # used in setpoint_raw attitude callback.
|
||||
# Note: PX4 expects normalized thrust values between 0 and 1, which means that
|
||||
# the scaling needs to be unitary and the inputs should be 0..1 as well.
|
||||
|
||||
# setpoint_position
|
||||
setpoint_position:
|
||||
tf:
|
||||
listen: false # enable tf listener (disable topic subscribers)
|
||||
frame_id: "map"
|
||||
child_frame_id: "target_position"
|
||||
rate_limit: 50.0
|
||||
mav_frame: LOCAL_NED
|
||||
|
||||
# setpoint_velocity
|
||||
setpoint_velocity:
|
||||
mav_frame: LOCAL_NED
|
||||
|
||||
# vfr_hud
|
||||
# None
|
||||
|
||||
# waypoint
|
||||
mission:
|
||||
pull_after_gcs: true # update mission if gcs updates
|
||||
use_mission_item_int: true # use the MISSION_ITEM_INT message instead of MISSION_ITEM
|
||||
# for uploading waypoints to FCU
|
||||
|
||||
# --- mavros extras plugins (same order) ---
|
||||
|
||||
# adsb
|
||||
# None
|
||||
|
||||
# debug_value
|
||||
# None
|
||||
|
||||
# distance_sensor
|
||||
## Currently available orientations:
|
||||
# Check http://wiki.ros.org/mavros/Enumerations
|
||||
##
|
||||
distance_sensor:
|
||||
hrlv_ez4_pub:
|
||||
id: 0
|
||||
frame_id: "hrlv_ez4_sonar"
|
||||
orientation: PITCH_270 # RPY:{0.0, 270.0, 0.0} - downward-facing
|
||||
field_of_view: 0.0 # XXX TODO
|
||||
send_tf: true
|
||||
sensor_position: {x: 0.0, y: 0.0, z: -0.1}
|
||||
lidarlite_pub:
|
||||
id: 1
|
||||
frame_id: "lidarlite_laser"
|
||||
orientation: PITCH_270
|
||||
field_of_view: 0.0 # XXX TODO
|
||||
send_tf: true
|
||||
sensor_position: {x: 0.0, y: 0.0, z: -0.1}
|
||||
sonar_1_sub:
|
||||
subscriber: true
|
||||
id: 2
|
||||
orientation: PITCH_270
|
||||
laser_1_sub:
|
||||
subscriber: true
|
||||
id: 3
|
||||
orientation: PITCH_270
|
||||
|
||||
# image_pub
|
||||
image:
|
||||
frame_id: "px4flow"
|
||||
|
||||
# fake_gps
|
||||
fake_gps:
|
||||
# select data source
|
||||
use_mocap: true # ~mocap/pose
|
||||
mocap_transform: true # ~mocap/tf instead of pose
|
||||
use_vision: false # ~vision (pose)
|
||||
# origin (default: Zürich)
|
||||
geo_origin:
|
||||
lat: 47.3667 # latitude [degrees]
|
||||
lon: 8.5500 # longitude [degrees]
|
||||
alt: 408.0 # altitude (height over the WGS-84 ellipsoid) [meters]
|
||||
eph: 2.0
|
||||
epv: 2.0
|
||||
satellites_visible: 5 # virtual number of visible satellites
|
||||
fix_type: 3 # type of GPS fix (default: 3D)
|
||||
tf:
|
||||
listen: false
|
||||
send: false # send TF?
|
||||
frame_id: "map" # TF frame_id
|
||||
child_frame_id: "fix" # TF child_frame_id
|
||||
rate_limit: 10.0 # TF rate
|
||||
gps_rate: 5.0 # GPS data publishing rate
|
||||
|
||||
# landing_target
|
||||
landing_target:
|
||||
listen_lt: false
|
||||
mav_frame: "LOCAL_NED"
|
||||
land_target_type: "VISION_FIDUCIAL"
|
||||
image:
|
||||
width: 640 # [pixels]
|
||||
height: 480
|
||||
camera:
|
||||
fov_x: 2.0071286398 # default: 115 [degrees]
|
||||
fov_y: 2.0071286398
|
||||
tf:
|
||||
send: true
|
||||
listen: false
|
||||
frame_id: "landing_target"
|
||||
child_frame_id: "camera_center"
|
||||
rate_limit: 10.0
|
||||
target_size: {x: 0.3, y: 0.3}
|
||||
|
||||
# mocap_pose_estimate
|
||||
mocap:
|
||||
# select mocap source
|
||||
use_tf: false # ~mocap/tf
|
||||
use_pose: true # ~mocap/pose
|
||||
|
||||
# odom
|
||||
odometry:
|
||||
fcu:
|
||||
odom_parent_id_des: "map" # desired parent frame rotation of the FCU's odometry
|
||||
odom_child_id_des: "iris_2/base_link" # desired child frame rotation of the FCU's odometry
|
||||
|
||||
# px4flow
|
||||
px4flow:
|
||||
frame_id: "px4flow"
|
||||
ranger_fov: 0.118682 # 6.8 degrees at 5 meters, 31 degrees at 1 meter
|
||||
ranger_min_range: 0.3 # meters
|
||||
ranger_max_range: 5.0 # meters
|
||||
|
||||
# vision_pose_estimate
|
||||
vision_pose:
|
||||
tf:
|
||||
listen: false # enable tf listener (disable topic subscribers)
|
||||
frame_id: "odom"
|
||||
child_frame_id: "vision_estimate"
|
||||
rate_limit: 10.0
|
||||
|
||||
# vision_speed_estimate
|
||||
vision_speed:
|
||||
listen_twist: true # enable listen to twist topic, else listen to vec3d topic
|
||||
twist_cov: true # enable listen to twist with covariance topic
|
||||
|
||||
# vibration
|
||||
vibration:
|
||||
frame_id: "iris_2/base_link"
|
||||
|
||||
# wheel_odometry
|
||||
wheel_odometry:
|
||||
count: 2 # number of wheels to compute odometry
|
||||
use_rpm: false # use wheel's RPM instead of cumulative distance to compute odometry
|
||||
wheel0: {x: 0.0, y: -0.15, radius: 0.05} # x-, y-offset (m,NED) and radius (m)
|
||||
wheel1: {x: 0.0, y: 0.15, radius: 0.05} # x-, y-offset (m,NED) and radius (m)
|
||||
send_raw: true # send wheel's RPM and cumulative distance (~/wheel_odometry/rpm, ~/wheel_odometry/distance)
|
||||
send_twist: false # send geometry_msgs/TwistWithCovarianceStamped instead of nav_msgs/Odometry
|
||||
frame_id: "odom" # origin frame
|
||||
child_frame_id: "iris_2/base_link" # body-fixed frame
|
||||
vel_error: 0.1 # wheel velocity measurement error 1-std (m/s)
|
||||
tf:
|
||||
send: false
|
||||
frame_id: "odom"
|
||||
child_frame_id: "iris_2/base_link"
|
||||
|
||||
# vim:set ts=2 sw=2 et:
|
|
@ -676,7 +676,7 @@ http://www.car-engineer.com/vehicle-inertia-calculation-tool/
|
|||
<visual>
|
||||
<origin xyz="0 -0.5 0.05" rpy="0 1.57 1.57"/>
|
||||
<geometry>
|
||||
<mesh filename="model://qrcode4-6/meshes/qrcode4-6.dae" scale="2 5 2"/>
|
||||
<mesh filename="model://apriltag3-5/meshes/apriltag3-5.dae" scale="2 5 2"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
|
||||
|
|
Loading…
Reference in New Issue