You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
In my ros1 & px4 project I've experienced that mavros only publishes the fused global position topics ~/global, ~/local, ~/rel_alt & ~/compass_hdg if the number of satellites visible is greater or equal to 15, despite correctly interpreting the mavlink data which is also getting published on the raw/fix topic.
Despite being in a relatively large field near a lake, during my flight tests if the weather is clear and I'm lucky I can sometimes get 15-20 visible satellites, however on cloudy days or just 'bad' days in general, I usually hover around 10 satellites with a 1 - 1.5 hdop/vdop. I'm wondering if this is desired behaviour or if I'm missing something, as I've read through the documentation and the global_position.cpp file, none of which state a required number of satellites beyond that of px4's internal required default 6 satellites in order to take off. Not only does my code expect msgs over the ~/global topic but also it expects a transform being published between the map and base_link frames which again is only published to /tf when the number of visible satellites >=15. For the time being I'm going to create a new node that reads the incoming msgs from the ~/raw/fix topic and forward it to the ~/global topic and /tf if the number of visible satellites is under 15 satellites, if that's not a good solution then I am all ears for a better stopgap or permanent fix.
Below is my config file that and pluginlists files I'm passing to mavros. Any guidance or help would be great. If i learn any more in the following days/weeks I'll publish here for posterity.
plugin_blacklist: # https://github.com/mavlink/mavros/tree/master/mavros_extras
- 3dr_radio
- actuator_control
- adsb
- cam_imu_sync
- cellular_status
- distance_sensor
- esc_status
- esc_telemtery
- esc_telemetry
- ftp
- geofence
- gps_rtk
- guided_target
- image_pub
- log_transfer
- mag_calibration_status
- manual_control
- mocap_pose_estimate
- mount_control
- nav_controller_output
- obstacle_distance
- play_tune
- px4flow
- rallypoint
- rangefinder
- rc_io
- safety_area
- terrain
- tunnel
- vibration
- vision_pose_estimate
- vision_speed_estimate
- wheel_odometry
- wind_estimation
- fake_gpsplugin_whitelist:
- 'sys_*'# this needs to be enabled for mavros to work
- 'setpoint_*'# loads all the setpoint plugins to allow for setting desitinations
- altitude
- camera
- command
- companion_process_status
- debug_value
- gps_input
- gps_status#- guided_target # removed to solve the `PositionTargetGlobal failed because no origin` error,
- hil
- home_position
- imu
- local_position
- odom # from mavros_extras https://github.com/mavlink/mavros/blob/master/mavros_extras/src/plugins/odom.cpp
- onboard_computer_status
- param
- trajectory
- waypoint
- heartbeat_status
# Common configuration for PX4 autopilot## node:startup_px4_usb_quirk: false# --- system plugins ---# sys_status & sys_time connection optionsconn:
heartbeat_rate: 1.0# send heartbeat rate in Hertztimeout: 10.0# heartbeat timeout in secondstimesync_rate: 0.0#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_statussys:
min_voltage: 10.0# diagnostics min voltage, use a vector i.e. [16.2, 16.0] for multiple batteries, up-to 10 are supported# to achieve the same on a ROS launch file do: <rosparam param="sys/min_voltage">[16.2, 16.0]</rosparam>disable_diag: false # disable all sys_status diagnostics, except heartbeat# sys_timetime:
time_ref_source: "fcu"# time_reference sourcetimesync_mode: MAVLINKtimesync_avg_alpha: 0.6# timesync averaging factor# --- mavros plugins (alphabetical order) ---# 3dr_radiotdr_radio:
low_rssi: 40# raw rssi lower level for diagnostics# actuator_control# None# commandcmd:
use_comp_id_system_control: false # quirk for some old FCUs# dummy# None# ftp# None# global_positionglobal_position:
frame_id: "map"# origin framechild_frame_id: "base_link"# body-fixed framerot_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 coordinatestf:
send: true # send TF?frame_id: "map"# TF frame_idglobal_frame_id: "earth"# TF earth frame_idchild_frame_id: "base_link"# TF child_frame_id# imu_pubimu:
frame_id: "odom"# need find actual valueslinear_acceleration_stdev: 0.0003angular_velocity_stdev: 0.0003490659 // 0.02 degreesorientation_stdev: 1.0magnetic_stdev: 0.0# local_positionlocal_position:
frame_id: "map"tf:
send: trueframe_id: "map"child_frame_id: "odom"send_fcu: false# param# None, used for FCU params# rc_io# None# safety_areasafety_area:
p1: {x: 1.0, y: 1.0, z: 1.0}p2: {x: -1.0, y: -1.0, z: -1.0}# setpoint_accelsetpoint_accel:
send_force: false# setpoint_attitudesetpoint_attitude:
reverse_thrust: false # allow reversed thrustuse_quaternion: false # enable PoseStamped topic subscribertf:
listen: false # enable tf listener (disable topic subscribers)frame_id: "map"child_frame_id: "target_attitude"rate_limit: 50.0setpoint_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_positionsetpoint_position:
tf:
listen: false # enable tf listener (disable topic subscribers)frame_id: "map"child_frame_id: "target_position"rate_limit: 50.0mav_frame: LOCAL_NED# setpoint_velocitysetpoint_velocity:
mav_frame: LOCAL_NED# vfr_hud# None# waypointmission:
pull_after_gcs: true # update mission if gcs updatesuse_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: 0frame_id: "hrlv_ez4_sonar"orientation: PITCH_270 # RPY:{0.0, 270.0, 0.0} - downward-facingfield_of_view: 0.0# XXX TODOsend_tf: truesensor_position: {x: 0.0, y: 0.0, z: -0.1}lidarlite_pub:
id: 1frame_id: "lidarlite_laser"orientation: PITCH_270field_of_view: 0.0# XXX TODOsend_tf: truesensor_position: {x: 0.0, y: 0.0, z: -0.1}sonar_1_sub:
subscriber: trueid: 2orientation: PITCH_270horizontal_fov_ratio: 1.0# horizontal_fov = horizontal_fov_ratio * msg.field_of_viewvertical_fov_ratio: 1.0# vertical_fov = vertical_fov_ratio * msg.field_of_view# custom_orientation: # Used for orientation == CUSTOM# roll: 0# pitch: 270# yaw: 0laser_1_sub:
subscriber: trueid: 3orientation: PITCH_270# image_pubimage:
frame_id: "px4flow"# fake_gpsfake_gps:
# select data sourceuse_mocap: true # ~mocap/posemocap_transform: true # ~mocap/tf instead of poseuse_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.0epv: 2.0satellites_visible: 5# virtual number of visible satellitesfix_type: 3# type of GPS fix (default: 3D)tf:
listen: falsesend: true # send TF?frame_id: "map"# TF frame_idchild_frame_id: "fix"# TF child_frame_idrate_limit: 10.0# TF rategps_rate: 5.0# GPS data publishing rate# landing_targetlanding_target:
listen_lt: falsemav_frame: "LOCAL_NED"land_target_type: "VISION_FIDUCIAL"image:
width: 640# [pixels]height: 480camera:
fov_x: 2.0071286398# default: 115 [degrees]fov_y: 2.0071286398tf:
send: truelisten: falseframe_id: "landing_target"child_frame_id: "camera_center"rate_limit: 10.0target_size: {x: 0.3, y: 0.3}# mocap_pose_estimatemocap:
# select mocap sourceuse_tf: false # ~mocap/tfuse_pose: true # ~mocap/pose# mount_controlmount:
debounce_s: 4.0err_threshold_deg: 10.0negate_measured_roll: falsenegate_measured_pitch: falsenegate_measured_yaw: false# odomodometry:
fcu:
odom_parent_id_des: "odom"# desired parent frame rotation of the FCU's odometryodom_child_id_des: "base_link"# desired child frame rotation of the FCU's odometry# px4flowpx4flow:
frame_id: "px4flow"ranger_fov: 0.118682# 6.8 degrees at 5 meters, 31 degrees at 1 meterranger_min_range: 0.3# metersranger_max_range: 5.0# meters# vision_pose_estimatevision_pose:
tf:
listen: false # enable tf listener (disable topic subscribers)frame_id: "odom"child_frame_id: "vision_estimate"rate_limit: 10.0# vision_speed_estimatevision_speed:
listen_twist: true # enable listen to twist topic, else listen to vec3d topictwist_cov: true # enable listen to twist with covariance topic# vibrationvibration:
frame_id: "base_link"# wheel_odometrywheel_odometry:
count: 2# number of wheels to compute odometryuse_rpm: false # use wheel's RPM instead of cumulative distance to compute odometrywheel0: {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/Odometryframe_id: "odom"# origin framechild_frame_id: "base_link"# body-fixed framevel_error: 0.1# wheel velocity measurement error 1-std (m/s)tf:
send: falseframe_id: "odom"child_frame_id: "base_link"# cameracamera:
frame_id: "base_link"
The text was updated successfully, but these errors were encountered:
In my ros1 & px4 project I've experienced that mavros only publishes the fused global position topics
~/global
,~/local
,~/rel_alt
&~/compass_hdg
if the number of satellites visible is greater or equal to 15, despite correctly interpreting the mavlink data which is also getting published on theraw/fix
topic.Despite being in a relatively large field near a lake, during my flight tests if the weather is clear and I'm lucky I can sometimes get 15-20 visible satellites, however on cloudy days or just 'bad' days in general, I usually hover around 10 satellites with a 1 - 1.5
hdop
/vdop
. I'm wondering if this is desired behaviour or if I'm missing something, as I've read through the documentation and the global_position.cpp file, none of which state a required number of satellites beyond that of px4's internal required default6
satellites in order to take off. Not only does my code expect msgs over the~/global
topic but also it expects a transform being published between themap
andbase_link
frames which again is only published to/tf
when the number of visible satellites >=15. For the time being I'm going to create a new node that reads the incoming msgs from the~/raw/fix
topic and forward it to the~/global
topic and/tf
if the number of visible satellites is under 15 satellites, if that's not a good solution then I am all ears for a better stopgap or permanent fix.Below is my
config
file that andpluginlists
files I'm passing to mavros. Any guidance or help would be great. If i learn any more in the following days/weeks I'll publish here for posterity.The text was updated successfully, but these errors were encountered: