Hello @Cliff-Wong,
Yes, I flew the drone around the room in position mode until the map was generated. I then flipped the remote to offboard with 'trajectory' set. Here are the files below:
/**
VOXL Vision PX4 Configuration File
version: don't touch this, used to keep track of changing config file formats
##############################################################################
MAVROS MAVSDK
##############################################################################
en_localhost_mavlink_udp:
If you are running MAVROS/MAVSDK onboard VOXL and wish to open access to
PX4 through a localhost UDP port simply ensure the follow feature is
enabled. This is set to true by default. This will allow one local process
to communicate with PX4 via port 14551 by default, NOT 14550 which is
reserved for connections outside the board. These separation prevents
conflicts between the two sockets. Both MAVROS and MAVSDK can be
configured to use this port.
localhost_udp_port_number:
Port number for localhost UDP socket, default 14551
##############################################################################
VIO
##############################################################################
en_vio:
Enable processing of VIO data from MPA to be sent to PX4 as mavlink
odometry messages. Enabled by default.
vio_pipe:
Primary pipe to subscribe to for VIO data. Must be a standard libmodal-pipe
vio_data_t type. Default is qvio. If no data is available on this pipe
then voxl-vision-hub will subscribe to secondary_vio_pipe instead.
secondary_vio_pipe:
Secondary pipe to subscribe to for VIO data. Must be a standard libmodal-pipe
vio_data_t type. Default is ov for openvins. If no data is available on this
pipe then voxl-vision-hub will subscribe to the primary vio_pipe instead.
Set to an empty string to disable. Default: ov
en_reset_vio_if_initialized_inverted:
For VIO algorithms like qVIO that can initialize in any orientation
and output their estimate of the gravity vector, we suggest leaving
this enabled to allow vvpx4 to automatically send the reset signal
back to the VIO pipe if VIO was initialized upside-down or sufficiently
off-level. Helpful if the user powers on a drone while carrying it to
the flight area and VIO starts too early.
vio_warmup_s:
Wait this for this amount of time of having good VIO data before
actually starting to send to PX4. This helps stop EKF2 getting
confused if VIO flickers in and out while struggling to init.
Set to 0 to disable the feature.
send_odom_while_failed:
On by default. Send Odometry messages to PX4 with a quality of -1 when
VIO indicates a failure so EKF2 can start dead reckoning.
This MAY need to be turned off with PX4 versions older than 1.14
since the quality metric was no implemented prior to PX4 1.14
##############################################################################
APQ8096-only Features
##############################################################################
en_set_clock_from_gps:
Enable setting the VOXL system time to GPS time if no NTP server can be
reached via network to set the time.
en_force_onboard_mav1_mode:
Force PX4 to use onboard mode for mavlink 1 channel which is the channel
apq8096 (VOXL1) uses to communicate UART Mavlink with PX4. Not applicable
to qrb5165-based platforms. Sets the MAV1_MODE PX4 param.
en_reset_px4_on_error:
Trigger a reboot of PX4 one some of PX4's unrecoverable errors,
Not applicable to qrb5165
Yaw estimate error & High Accelerometer Bias and both detected
##############################################################################
Misc Features
##############################################################################
horizon_cal_tolerance:
Allowable standard deviation in roll/pitch values to consider the drone
stable enough in flight to do a PX4 horizon calibration. Default is 0.45,
you can increase this slightly if flying in a small indoor area or with
a drone that does not hold still very well.
See https://docs.modalai.com/calibrate-px4-horizon/
en_hitl:
Enable Hardware In The Loop (HITL) testing extensions. Disabled by default.
##############################################################################
offboard mode config
##############################################################################
offboard_mode: The following are valid strings
off: VVPX4 will not send any offboard commands to PX4
figure_eight: Default value, VVPX4 commands PX4 to fly a figure 8 path
follow_tag: Drone will follow an apriltag around. Very dangerous, not
recommended for customer use, for ModalAI R&D only.
trajectory: VVPX4 receives polynomial trajectories by pipe and commands
PX4 to follow the trajectory path. Still in development.
backtrack: Drone will replay, in reverse order, the last few seconds of it's
position including yaw. This is useful when the drone loses
the communication link and needs to get back to a place where
it is able to regain the link. This mode will notice when the
RC link goes away and sends a command to px4 to enter offboard mode.
wps: read waypoints in local coordinate system
follow_tag_id:
Apriltag ID to follow in follow_tag mode
figure_eight_move_home:
Enable by default, resets the center of the figure 8 path to wherever
the drone is when flipped into offboard mode. When disabled, the drone
will quickly fly back to the XYZ point 0,0,-1.5 in VIO frame before
starting the figure 8. Disabling this feature can be dangerous if VIO
has drifted significantly.
wps_move_home:
Enable by default, resets the center of the wps path to wherever
the drone is when flipped into offboard mode. When disabled, the drone
will quickly fly back to the XYZ point 0,0,-1.5 in VIO frame before
starting the figure 8. Disabling this feature can be dangerous if VIO
has drifted significantly.
robot_radius:
Robot radius to use when checking collisions within the trajectory monitor.
The trajectory monitor is only active when in trajectory mode
collision_sampling_dt:
The time step to sample along the polynomials by when checking for collisions
in the collision monitor.
max_lookahead_distance:
Maximum distance to look along the trajectory. Sensor data further out can be
unrealiable so keeping this value small reduces false positives
backtrack_seconds:
Number of seconds worth of position data to store for replay in backtrack mode.
backtrack_rc_chan:
RC channel to monitor for transitions into and out of backtrack mode.
backtrack_rc_thresh:
Value above which backtrack is considered enabled on the configured RC channel.
##############################################################################
Fixed Frame Tag Relocalization
##############################################################################
en_tag_fixed_frame:
Enable fixed frame relocalization via voa_inputs.
See: https://docs.modalai.com/voxl-vision-px4-apriltag-relocalization/
fixed_frame_filter_len:
Length of the moving average filter to use for smooth relocalization
when a tag is detected. Default is 5, a longer filter will result in
smoother behavior when a new tag comes into view. Set to 1 to do no
filtering at all and assume every tag detection is accurate.
en_transform_mavlink_pos_setpoints_from_fixed_frame:
When enabled, mavlink position_target_local_ned_t commands received on
via UDP will be assumed to be in fixed frame and are then transformed
to local frame before being sent to PX4. This allows offboard mode
position commands from MAVROS/MAVSDK to be in fixed frame relative to
voa_inputs even though PX4/EKF2 operates in local frame relative to where
VIO initialized.
##############################################################################
Collision Prevention (VOA)
Settings for configuring Mavlink data sent to Autopilot for VOA
##############################################################################
en_voa:
Enable processing of DFS and TOF data to be sent to PX4 as mavlink
obstacle_distance messages for collision prevention in position mode.
voa_lower_bound_m & voa_upper_bound_m:
VOA ignores obstacles above and below the upper and lower bounds.
Remember, Z points downwards in body and NED frames, so the lower bound
is a positive number, and the upper bound is a negative number.
Defaults are lower: 0.15 upper: -0.15 Units are in meters.
voa_memory_s:
number of seconds to keep track of sensor readings for VOA
default: 1.0
voa_max_pc_per_fusion:
maximum number of sensor samples (points clouds) to fuse for every
mavlink transmision. Default is 100 so that voa_memory_s determines
when to discard old data instead. set this to 1 if you only want to use
the most recent sensor sample for example. If you start severly limiting
the number of point clouds used per fusion, you will also need to lower
voa_pie_threshold.
voa_pie_min_dist_m:
minimum distance from the drone's center of mass to consider a sensor
sample a valid point for mavlink transmission.
voa_pie_max_dist_m:
minimum distance from the drone's center of mass to consider a sensor
sample a valid point for mavlink transmission. Note this is and can be
different from the individual sensor limits.
voa_pie_under_trim_m:
VOA discards points in a bubble under the drone with this radius.
default 1.0. This helps the drone approach an obstacle, stop
ascend, and continue forward smoothly over the top.
voa_pie_threshold:
Minimum number of points that must appear in and adjacent to a pie
segment to consider it populated. Default 3
voa_send_rate_hz:
Rate to send VOA mavlink data to autopilot. Independent from the
sensor input rates. Default 20
voa_pie_slices:
number of slices to divide the 360 degree span around the drone into.
default 36 (10 degree slices)
voa_pie_bin_depth_m:
Radial depth of each bin during the pie binning step. Default 0.15
##############################################################################
Collision Prevention (VOA) Input Configuration
Settings for configuring pipe data sources for VOA
##############################################################################
voa_inputs:
Array of pipes to subscribe to for use with VOA, up to 10 supported
Each entry has 4 fields:
Fields:
enabled: true or false, it's safe to leave this enabled when the pipe is missing
type: can be point_cloud, tof, or rangefinder
input_pipe: pipe name, e.g. stereo_front_pc, rangefinders, tof, etc
frame: frame of reference, should be listed in /etc/modalai/extrinsics/conf
max_depth: trim away points with z greater than this
min_depth: trim away points with z less than this
cell_size: size of 3d voxel grid cells, increase for more downsampling
threshold: num points that must exist in or adjacent to a cell to consider it
populated, set to 1 to disable threasholding
x_fov_deg: FOV of the sensor in the x direction, typically width
y_fov_deg: FOV of the sensor in the y direction, typically height
conf_cutoff: discard points below this confidence, only applicable to TOF
*/
{
"config_file_version": 1,
"en_localhost_mavlink_udp": false,
"localhost_udp_port_number": 14551,
"en_vio": true,
"vio_pipe": "qvio",
"secondary_vio_pipe": "ov",
"vfc_vio_pipe": "ov",
"en_reset_vio_if_initialized_inverted": true,
"vio_warmup_s": 3,
"send_odom_while_failed": true,
"horizon_cal_tolerance": 0.5,
"en_hitl": false,
"offboard_mode": "trajectory",
"follow_tag_id": 0,
"figure_eight_move_home": true,
"robot_radius": 0.300000011920929,
"collision_sampling_dt": 0.1,
"max_lookahead_distance": 1,
"backtrack_seconds": 60,
"backtrack_rc_chan": 8,
"backtrack_rc_thresh": 1500,
"wps_move_home": true,
"wps_stride": 0,
"wps_timeout": 0,
"wps_damp": 1,
"wps_vfc_mission": true,
"wps_vfc_mission_loop": false,
"wps_vfc_mission_to_ramp": 25,
"wps_vfc_mission_to_kp": 0.10000000149011612,
"wps_vfc_mission_cruise_speed": 1,
"en_tag_fixed_frame": false,
"fixed_frame_filter_len": 5,
"en_transform_mavlink_pos_setpoints_from_fixed_frame": false,
"vfc_rate": 100,
"vfc_rc_chan_min": 980,
"vfc_rc_chan_max": 2020,
"vfc_thrust_ch": 3,
"vfc_roll_ch": 1,
"vfc_pitch_ch": 2,
"vfc_yaw_ch": 4,
"vfc_submode_ch": 6,
"vfc_alt_mode_rc_min": 0,
"vfc_alt_mode_rc_max": 0,
"vfc_flow_mode_rc_min": 0,
"vfc_flow_mode_rc_max": 0,
"vfc_hybrid_flow_mode_rc_min": 0,
"vfc_hybrid_flow_mode_rc_max": 0,
"vfc_position_mode_rc_min": 0,
"vfc_position_mode_rc_max": 2100,
"vfc_traj_mode_rc_min": 0,
"vfc_traj_mode_rc_max": 0,
"vfc_yaw_deadband": 30,
"vfc_vxy_deadband": 50,
"vfc_vz_deadband": 150,
"vfc_min_thrust": 0,
"vfc_max_thrust": 0.800000011920929,
"vfc_tilt_max": 0.43599998950958252,
"vfc_yaw_rate_max": 3,
"vfc_thrust_hover": 0.5,
"vfc_vz_max": 1,
"vfc_kp_z": 5.2899999618530273,
"vfc_kd_z": 5.9800000190734863,
"vfc_vxy_max": 3,
"vfc_kp_xy": 0.63999998569488525,
"vfc_kd_xy": 2.559999942779541,
"vfc_kp_z_vio": 5.2899999618530273,
"vfc_kd_z_vio": 5.9800000190734863,
"vfc_kp_xy_vio": 3.2400000095367432,
"vfc_kd_xy_vio": 3.9600000381469727,
"vfc_w_filt_xy_vio": 10,
"vfc_w_filt_xy_flow": 3,
"vfc_vel_ff_factor_vio": 0.899999976158142,
"vfc_xy_acc_limit_vio": 2.5,
"vfc_max_z_delta": 3,
"vfc_att_transition_time": 0.5,
"vfc_stick_move_threshold": 30,
"vfc_flow_transition_time": 1,
"vfc_q_min": 10,
"vfc_points_min": 7,
"vfc_en_submode_announcement": 1,
"vfc_disable_fallback": false,
"vfc_traj_csv": "/data/voxl-vision-hub/traj.csv",
"en_voa": true,
"voa_upper_bound_m": -0.15000000596046448,
"voa_lower_bound_m": 0.15000000596046448,
"voa_voa_memory_s": 1,
"voa_max_pc_per_fusion": 100,
"voa_pie_max_dist_m": 20,
"voa_pie_min_dist_m": 0.25,
"voa_pie_under_trim_m": 1,
"voa_pie_threshold": 3,
"voa_send_rate_hz": 20,
"voa_pie_slices": 36,
"voa_pie_bin_depth_m": 0.15000000596046448,
"voa_inputs": [{
"enabled": true,
"type": "point_cloud",
"input_pipe": "dfs_point_cloud",
"frame": "stereo_l",
"max_depth": 8,
"min_depth": 0.300000011920929,
"cell_size": 0.079999998211860657,
"threshold": 4,
"x_fov_deg": 68,
"y_fov_deg": 56,
"conf_cutoff": 0
}, {
"enabled": true,
"type": "point_cloud",
"input_pipe": "stereo_front_pc",
"frame": "stereo_front_l",
"max_depth": 8,
"min_depth": 0.300000011920929,
"cell_size": 0.079999998211860657,
"threshold": 4,
"x_fov_deg": 68,
"y_fov_deg": 56,
"conf_cutoff": 0
}, {
"enabled": true,
"type": "point_cloud",
"input_pipe": "stereo_rear_pc",
"frame": "stereo_rear_l",
"max_depth": 8,
"min_depth": 0.300000011920929,
"cell_size": 0.079999998211860657,
"threshold": 4,
"x_fov_deg": 68,
"y_fov_deg": 56,
"conf_cutoff": 0
}, {
"enabled": true,
"type": "tof",
"input_pipe": "tof",
"frame": "tof",
"max_depth": 6,
"min_depth": 0.15000000596046448,
"cell_size": 0.079999998211860657,
"threshold": 3,
"x_fov_deg": 106.5,
"y_fov_deg": 85.0999984741211,
"conf_cutoff": 125
}, {
"enabled": true,
"type": "rangefinder",
"input_pipe": "rangefinders",
"frame": "body",
"max_depth": 8,
"min_depth": 0.300000011920929,
"cell_size": 0.079999998211860657,
"threshold": 4,
"x_fov_deg": 68,
"y_fov_deg": 56,
"conf_cutoff": 0
}]
}
/**
This file contains configuration that's specific to voxl-open-vins-server.
NOTE: all time variables are measured in seconds
OpenVins param breakdown:
do_fej: whether or not to do first estimate Jacobians
imu_avg: whether or not use imu message averaging
use_rk4_integration: if we should use Rk4 imu integration.
cam_to_imu_refinement: whether or not to refine the imu-to-camera pose
cam_intrins_refinement: whether or not to refine camera intrinsics
cam_imu_ts_refinement: whether or not to calibrate cam to IMU time offset
max_clone_size: max clone size of sliding window
max_slam_features: max number of estimated SLAM features
max_slam_in_update: max number of SLAM features in a single EKF update
max_msckf_in_update: max number of MSCKF features used at an image timestep
Feature Reps can be any of the following:
0 - GLOBAL_3D
1 - GLOBAL_FULL_INVERSE_DEPTH
2 - ANCHORED_3D
3 - ANCHORED_FULL_INVERSE_DEPTH
4 - ANCHORED_MSCKF_INVERSE_DEPTH
5 - ANCHORED_INVERSE_DEPTH_SINGLE
feat_rep_msckf: (int) what representation our msckf features are in
feat_rep_slam: (int) what representation our slam features are in
cam_imu_time_offset: time offset between camera and IMU
slam_delay: delay that we should wait from init before estimating SLAM features
gravity_mag: gravity magnitude in the global frame
init_window_time: amount of time to initialize over
init_imu_thresh: variance threshold on our accel to be classified as moving
imu_sigma_w: gyroscope white noise (rad/s/sqrt(hz))
imu_sigma_wb: gyroscope random walk (rad/s^2/sqrt(hz))
imu_sigma_a: accelerometer white noise (m/s^2/sqrt(hz))
imu_sigma_ab: accelerometer random walk (m/s^3/sqrt(hz))
imu_sigma_w_2: gyroscope white noise covariance
imu_sigma_wb_2: gyroscope random walk covariance
imu_sigma_a_2: accelerometer white noise covariance
imu_sigma_ab_2: accelerometer random walk covariance
****_chi2_multiplier: what chi-squared multipler we should apply
****_sigma_px: noise sigma for our raw pixel measurements
****_sigma_px_sq: covariance for our raw pixel measurements
use_stereo: if feed_measurement_camera is called with more than one
image, this determines behavior. if true, they are treated as a stereo
pair, otherwise treated as binocular system
if you enable a camera with stereo in the name, this will be set to true
automatically
try_zupt: if we should try to use zero velocity update
zupt_max_velocity: max velocity we will consider to try to do a zupt
zupt_only_at_beginning: if we should only use the zupt at the very beginning
zupt_noise_multiplier: multiplier of our zupt measurement IMU noise matrix
zupt_max_disparity: max disparity we will consider to try to do a zupt
NOTE: set zupt_max_disparity to 0 for only imu based zupt, and
zupt_chi2_multipler to 0 for only display based zupt
num_pts: number of points we should extract and track in each image frame
fast_threshold: fast extraction threshold
grid_x: number of column-wise grids to do feature extraction in
grid_y: number of row-wise grids to do feature extraction in
min_px_dist: after doing KLT track will remove any features closer than this
knn_ratio: KNN ration between top two descriptor matchers for good match
downsample_cams: will half image resolution
use_nultithreading: if we should use multi-threading for stereo matching
use_mask: if we should load a mask and use it to reject invalid features
*/
{
"en_auto_reset": true,
"auto_reset_max_velocity": 20,
"auto_reset_max_v_cov_instant": 0.10000000149011612,
"auto_reset_max_v_cov": 0.10000000149011612,
"auto_reset_max_v_cov_timeout_s": 0.5,
"auto_reset_min_features": 1,
"auto_reset_min_feature_timeout_s": 3,
"auto_fallback_timeout_s": 3,
"auto_fallback_min_v": 0.600000023841858,
"en_cont_yaw_checks": false,
"fast_yaw_thresh": 5,
"fast_yaw_timeout_s": 1.75,
"do_fej": true,
"imu_avg": true,
"use_rk4_integration": true,
"cam_to_imu_refinement": true,
"cam_intrins_refinement": true,
"cam_imu_ts_refinement": true,
"max_clone_size": 8,
"max_slam_features": 35,
"max_slam_in_update": 10,
"max_msckf_in_update": 10,
"feat_rep_msckf": 4,
"feat_rep_slam": 4,
"cam_imu_time_offset": 0,
"slam_delay": 1,
"gravity_mag": 9.80665,
"init_window_time": 1,
"init_imu_thresh": 1,
"imu_sigma_w": 0.00013990944749616306,
"imu_sigma_wb": 4.1189724174615527e-07,
"imu_sigma_a": 0.0038947538150776763,
"imu_sigma_ab": 5.538346201712153e-05,
"msckf_chi2_multiplier": 1,
"slam_chi2_multiplier": 40,
"zupt_chi2_multiplier": 1,
"refine_features": true,
"pyr_levels": 6,
"grid_x": 5,
"grid_y": 5,
"msckf_sigma_px": 1,
"slam_sigma_px": 1.8,
"zupt_sigma_px": 1,
"try_zupt": true,
"zupt_max_velocity": 0.03,
"zupt_only_at_beginning": true,
"zupt_noise_multiplier": 1,
"zupt_max_disparity": 8,
"init_dyn_use": false,
"triangulate_1d": false,
"max_runs": 5,
"init_lamda": 0.001,
"max_lamda": 10000000000,
"min_dx": 1e-06,
"min_dcost": 1e-06,
"lam_mult": 10,
"min_dist": 0.1,
"max_dist": 60,
"max_baseline": 40,
"max_cond_number": 600000,
"use_mask": false,
"use_stereo": false,
"use_baro": false,
"num_opencv_threads": 4,
"fast_threshold": 15,
"histogram_method": 1,
"knn_ratio": 0.7,
"takeoff_accel_threshold": 0.5,
"takeoff_threshold": -0.1,
"use_stats": false,
"max_allowable_cep": 1,
"en_force_init": false,
"en_force_ned_2_flu": false,
"en_imu_frame_output": false,
"track_frequency": 15,
"publish_frequency": 5,
"en_vio_always_on": true,
"en_ext_feature_tracker": false,
"en_gpu_for_tracking": true,
"num_features_to_track": 20,
"raansac_gn": false,
"raansac_tri": true,
"en_thermal_enhance": false,
"en_overlay_landscape": false,
"thermal_brightness": 1,
"thermal_brightness_bos": 1
}