-
Notifications
You must be signed in to change notification settings - Fork 197
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Remove thrust from altitude graph. Add HDOP, VDOP, and speed accuracy to GPS. Fix vibration instance 3 label. #284
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -194,13 +194,13 @@ def generate_plots(ulog, px4_ulog, db_data, vehicle_data, link_to_3d_page, | |
data_plot.add_graph(['baro_alt_meter'], colors8[1:2], ['Barometer Altitude']) | ||
data_plot.change_dataset('vehicle_global_position') | ||
data_plot.add_graph(['alt'], colors8[2:3], ['Fused Altitude Estimation']) | ||
# If there is no altitude setpoint and we don't check, the Y axis always starts at 0. | ||
data_plot.change_dataset('position_setpoint_triplet') | ||
data_plot.add_circle(['current.alt'], [plot_config['mission_setpoint_color']], | ||
['Altitude Setpoint']) | ||
data_plot.change_dataset(actuator_controls_0.thrust_sp_topic) | ||
if actuator_controls_0.thrust_z_neg is not None: | ||
data_plot.add_graph([lambda data: ('thrust', actuator_controls_0.thrust_z_neg*100)], | ||
colors8[6:7], ['Thrust [0, 100]']) | ||
if 'position_setpoint_triplet' in data and 'current' in data['position_setpoint_triplet']: | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Why is this changed? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Without this, the Y axis range always starts at 0. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Well this isn't correct though. How did you test this? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Do you have a log where this doesn't work? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Check any log that has some mission on https://logs.px4.io/browse, eg https://logs.px4.io/plot_app?log=22a7603d-edf4-476a-8b0e-0aa0a73b107b |
||
current = data['position_setpoint_triplet']['current'] | ||
if 'alt' in current and current['alt'] is not None: | ||
data_plot.add_circle(['current.alt'], [plot_config['mission_setpoint_color']], | ||
['Altitude Setpoint']) | ||
plot_flight_modes_background(data_plot, flight_mode_changes, vtol_states) | ||
|
||
if data_plot.finalize() is not None: plots.append(data_plot) | ||
|
@@ -667,7 +667,7 @@ def generate_plots(ulog, px4_ulog, db_data, vehicle_data, link_to_3d_page, | |
|
||
data_plot.change_dataset('vehicle_imu_status', 3) | ||
data_plot.add_graph(['accel_vibration_metric'], colors8[3:4], | ||
['Accel 3 Vibration Level [rad/s]']) | ||
['Accel 3 Vibration Level [m/s^2]']) | ||
|
||
data_plot.add_horizontal_background_boxes( | ||
['green', 'orange', 'red'], [4.905, 9.81]) | ||
|
@@ -806,8 +806,11 @@ def generate_plots(ulog, px4_ulog, db_data, vehicle_data, link_to_3d_page, | |
title='GPS Uncertainty', y_range=Range1d(0, 40), | ||
plot_height='small', changed_params=changed_params, | ||
x_range=x_range) | ||
data_plot.add_graph(['eph', 'epv', 'satellites_used', 'fix_type'], colors8[::2], | ||
['Horizontal position accuracy [m]', 'Vertical position accuracy [m]', | ||
data_plot.add_graph(['eph', 'epv', 'hdop', 'vdop', 's_variance_m_s', | ||
'satellites_used', 'fix_type'], colors8, | ||
['Horizontal position accuracy [m]', | ||
'Vertical position accuracy [m]', 'Horizontal dilution of precision [m]', | ||
'Vertical dilution of precision [m]', 'Speed accuracy [m/s]', | ||
'Num Satellites used', 'GPS Fix']) | ||
if data_plot.finalize() is not None: plots.append(data_plot) | ||
|
||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Can you separate the commit and provide the reason for the change for future reference?
We could also shift the thrust into the range of the altitude instead.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Split the commit and added a comment.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
#287