Skip to content

Commit

Permalink
clippy fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
astraw committed Nov 18, 2024
1 parent 19c0440 commit 25ded6d
Show file tree
Hide file tree
Showing 29 changed files with 109 additions and 149 deletions.
19 changes: 8 additions & 11 deletions bg-movie-writer/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -135,18 +135,15 @@ where
{
None,
Mp4Writer(Mp4Writer<'lib, T>),
FfmpegWriter(MyFfmpegWriter),
FfmpegWriter(Box<MyFfmpegWriter>),
}

impl<'lib, T> RawWriter<'lib, T>
where
T: Write + Seek,
{
fn is_none(&self) -> bool {
match self {
Self::None => true,
_ => false,
}
matches!(self, Self::None)
}
}

Expand Down Expand Up @@ -197,8 +194,8 @@ impl MyFfmpegWriter {
count: 0,
})
}
fn write<'a, IM, FMT>(
&'a mut self,
fn write<IM, FMT>(
&mut self,
frame: &IM,
timestamp: chrono::DateTime<chrono::Local>,
) -> Result<()>
Expand All @@ -220,7 +217,7 @@ impl MyFfmpegWriter {
}
}

fn launch_runner<'lib>(
fn launch_runner(
format_str_mp4: String,
recording_config: ci2_remote_control::RecordingConfig,
size: usize,
Expand Down Expand Up @@ -307,10 +304,10 @@ fn launch_runner<'lib>(
));
}
Ffmpeg(c) => {
raw = RawWriter::FfmpegWriter(thread_try!(
raw = RawWriter::FfmpegWriter(Box::new(thread_try!(
err_tx,
MyFfmpegWriter::new(&mp4_filename, &c)
));
MyFfmpegWriter::new(&mp4_filename, c)
)));
}
};
}
Expand Down
4 changes: 2 additions & 2 deletions braid-offline/src/bin/compute-flydra1-compat.rs
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ pub struct FilteredObservations {
}

fn no_data_row(obj_id: u32, frame: SyncFno) -> KalmanEstimatesRow {
let nan: f64 = std::f64::NAN;
let nan: f64 = f64::NAN;

KalmanEstimatesRow {
obj_id,
Expand Down Expand Up @@ -158,7 +158,7 @@ fn save_data_association_ascending<R1: Read, R2: Read>(
let mut kalman_estimates_iter =
kalman_estimates_reader.into_deserialize::<KalmanEstimatesRow>();
let kest_frame_iter = AscendingGroupIter::new(&mut kalman_estimates_iter).early_eof_ok();
let nan: f32 = std::f32::NAN;
let nan: f32 = f32::NAN;

let opt_next_da_row = da_row_frame_iter.next();
if opt_next_da_row.is_none() {
Expand Down
6 changes: 3 additions & 3 deletions braid-process-video/src/output_braidz.rs
Original file line number Diff line number Diff line change
Expand Up @@ -188,11 +188,11 @@ impl BraidStorage {
let pt = flydra_types::FlydraRawUdpPoint {
x0_abs: *xy.0,
y0_abs: *xy.1,
area: std::f64::NAN,
area: f64::NAN,
maybe_slope_eccentricty: None,
cur_val: 0,
mean_val: std::f64::NAN,
sumsqf_val: std::f64::NAN,
mean_val: f64::NAN,
sumsqf_val: f64::NAN,
};
flydra2::NumberedRawUdpPoint {
idx: idx.try_into().unwrap(),
Expand Down
2 changes: 1 addition & 1 deletion braid/braid-run/src/main.rs
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ fn launch_strand_cam(
let cam_name = camera.name.clone();

let mut exec = std::process::Command::new(&exe);
let args = compute_strand_cam_args(&camera, mainbrain_internal_addr)?;
let args = compute_strand_cam_args(camera, mainbrain_internal_addr)?;
exec.args(&args);
debug!("exec: {:?}", exec);
let mut obj = exec.spawn().context(format!(
Expand Down
4 changes: 2 additions & 2 deletions braid/braid-run/src/mainbrain.rs
Original file line number Diff line number Diff line change
Expand Up @@ -379,7 +379,7 @@ async fn launch_braid_http_backend(
let urls = mainbrain_server_info.build_urls()?;
for url in urls.iter() {
info!("Predicted URL: {url}");
if !flydra_types::is_loopback(&url) {
if !flydra_types::is_loopback(url) {
println!("QR code for {url}");
display_qr_url(&format!("{url}"));
}
Expand Down Expand Up @@ -1153,7 +1153,7 @@ pub(crate) async fn do_run_forever(
packet.block_id,
);

assert!(packet.points.len() < u8::max_value() as usize);
assert!(packet.points.len() < u8::MAX as usize);
let points = packet
.points
.into_iter()
Expand Down
2 changes: 1 addition & 1 deletion braidz-parser/braidz-chunked-iter/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ where
));
}
ChunkStartAndDuration::Frame(start_frame, n_frames_in_chunk) => {
let next_u64: u64 = next.try_into().unwrap();
let next_u64: u64 = next.into();
let n_frames_in_chunk_u64: u64 = (*n_frames_in_chunk).try_into().unwrap();
let stop_dur = n_frames_in_chunk_u64 * next_u64;
stop_frame = Some(*start_frame + stop_dur);
Expand Down
2 changes: 1 addition & 1 deletion braidz-parser/src/incremental_parser.rs
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ impl<R: Read + Seek> IncrementalParser<R, ArchiveOpened> {
.unwrap();

// Parse fps and tracking parameters from textlog.
let mut expected_fps = std::f64::NAN;
let mut expected_fps = f64::NAN;
let tracking_params: Option<TrackingParams> = {
let mut fname = self.archive.path_starter();
fname.push(flydra_types::TEXTLOG_CSV_FNAME);
Expand Down
8 changes: 4 additions & 4 deletions ci2-pyloncxx/src/feature_cache.rs
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ impl PfsCache {
strict,
})
}
pub(crate) fn to_string(&self) -> String {
pub(crate) fn to_header_string(&self) -> String {
// Again, I could not find any documentation about the PFS (Pylon
// Feature System) format, so this is all a guess.
let mut out_lines = self.headers.clone();
Expand All @@ -62,7 +62,7 @@ impl PfsCache {
pub(crate) fn update(&mut self, key: &str, value: String) {
let mut found = false;
for node in self.nodes.iter_mut() {
if &node.0 == key {
if node.0 == key {
if found && self.strict {
panic!("Key \"{}\" exists more than once in PFS.", key);
}
Expand All @@ -87,7 +87,7 @@ pub(crate) trait PfsTrackedIntegerNode {
impl PfsTrackedIntegerNode for pylon_cxx::IntegerNode {
fn set_value_pfs(&mut self, pfs: &mut PfsCache, new_value: i64) -> pylon_cxx::PylonResult<()> {
self.set_value(new_value)?;
pfs.update(self.name(), format!("{}", new_value));
pfs.update(self.name(), new_value.to_string());
Ok(())
}
}
Expand All @@ -99,7 +99,7 @@ pub(crate) trait PfsTrackedEnumNode {
impl PfsTrackedEnumNode for pylon_cxx::EnumNode {
fn set_value_pfs(&mut self, pfs: &mut PfsCache, new_value: &str) -> pylon_cxx::PylonResult<()> {
self.set_value(new_value)?;
pfs.update(self.name(), format!("{}", new_value));
pfs.update(self.name(), new_value.to_string());
Ok(())
}
}
Expand Down
57 changes: 23 additions & 34 deletions ci2-pyloncxx/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -96,11 +96,8 @@ impl Drop for PylonTerminateGuard {
}
}

pub fn make_singleton_guard<'a>(
_pylon_module: &dyn ci2::CameraModule<
CameraType = WrappedCamera<'a>,
Guard = PylonTerminateGuard,
>,
pub fn make_singleton_guard(
_pylon_module: &dyn ci2::CameraModule<CameraType = WrappedCamera, Guard = PylonTerminateGuard>,
) -> ci2::Result<PylonTerminateGuard> {
Ok(PylonTerminateGuard {
already_dropped: false,
Expand Down Expand Up @@ -331,14 +328,12 @@ impl<'a> WrappedCamera<'a> {
store_fno: 0,
last_rollover: 0,
})
} else if model == "Emulation" {
// As of Pylon 6.2.0, emulation with PYLON_CAMEMU does
// not set frame number.
FramecoutingMethod::IgnoreDevice(0)
} else {
if model == "Emulation" {
// As of Pylon 6.2.0, emulation with PYLON_CAMEMU does
// not set frame number.
FramecoutingMethod::IgnoreDevice(0)
} else {
FramecoutingMethod::TrustDevice
}
FramecoutingMethod::TrustDevice
};

let cam = tl_factory
Expand Down Expand Up @@ -457,12 +452,12 @@ impl<'a> WrappedCamera<'a> {
});
}
}
return Err(Error::OtherError {
Err(Error::OtherError {
msg: format!("requested camera '{}' was not found", name),
#[cfg(feature = "backtrace")]
backtrace: std::backtrace::Backtrace::capture(),
}
.into());
.into())
}

fn exposure_time_param_name(&self) -> &'static str {
Expand Down Expand Up @@ -623,7 +618,7 @@ impl<'a> ci2::Camera for WrappedCamera<'a> {
// Ideally we would simply call camera.node_map().map_pylon_err()?.save_to_string() here,
// but this requires stopping the camera. Instead we cache the node
// values.
Ok(self.pfs_cache.lock().to_string())
Ok(self.pfs_cache.lock().to_header_string())
}

/// Return the sensor width in pixels
Expand Down Expand Up @@ -912,12 +907,10 @@ impl<'a> ci2::Camera for WrappedCamera<'a> {
match val.as_ref() {
"Off" => Ok(ci2::TriggerMode::Off),
"On" => Ok(ci2::TriggerMode::On),
s => {
return Err(ci2::Error::from(format!(
"unexpected TriggerMode enum string: {}",
s
)));
}
s => Err(ci2::Error::from(format!(
"unexpected TriggerMode enum string: {}",
s
))),
}
}
fn set_trigger_mode(&mut self, value: TriggerMode) -> ci2::Result<()> {
Expand Down Expand Up @@ -1002,12 +995,10 @@ impl<'a> ci2::Camera for WrappedCamera<'a> {
"FrameBurstStart" => Ok(ci2::TriggerSelector::FrameBurstStart),
"FrameStart" => Ok(ci2::TriggerSelector::FrameStart),
"ExposureActive" => Ok(ci2::TriggerSelector::ExposureActive),
s => {
return Err(ci2::Error::from(format!(
"unexpected TriggerSelector enum string: {}",
s
)));
}
s => Err(ci2::Error::from(format!(
"unexpected TriggerSelector enum string: {}",
s
))),
}
}
fn set_trigger_selector(&mut self, value: TriggerSelector) -> ci2::Result<()> {
Expand Down Expand Up @@ -1093,7 +1084,7 @@ impl<'a> ci2::Camera for WrappedCamera<'a> {
let cam = self.inner.lock();

// Wait for an image and then retrieve it. A timeout of 99999 ms is used.
cam.retrieve_result(99999, &mut *gr, pylon_cxx::TimeoutHandling::ThrowException)
cam.retrieve_result(99999, &mut gr, pylon_cxx::TimeoutHandling::ThrowException)
.map_pylon_err()?;

let now = chrono::Utc::now(); // earliest possible timestamp
Expand Down Expand Up @@ -1246,12 +1237,10 @@ fn str_to_auto_mode(val: &str) -> ci2::Result<ci2::AutoMode> {
"Off" => Ok(ci2::AutoMode::Off),
"Once" => Ok(ci2::AutoMode::Once),
"Continuous" => Ok(ci2::AutoMode::Continuous),
s => {
return Err(ci2::Error::from(format!(
"unexpected AutoMode enum string: {}",
s
)));
}
s => Err(ci2::Error::from(format!(
"unexpected AutoMode enum string: {}",
s
))),
}
}

Expand Down
2 changes: 1 addition & 1 deletion ci2-remote-control/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -382,7 +382,7 @@ impl std::fmt::Display for FfmpegCodecArgs {
.codec
.as_ref()
.map(|c| format!("-c:v {c}"))
.unwrap_or_else(|| "".to_string());
.unwrap_or_default();
let post = arg_fmt(self.post_codec_args.as_ref());
write!(f, "ffmpeg {pre} {codec} {post}")
}
Expand Down
2 changes: 1 addition & 1 deletion flydra-feature-detector/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -648,7 +648,7 @@ impl FlydraFeatureDetector {
// the camera driver.
acquire_stamp.as_f64() - trigger_stamp.as_f64()
}
None => std::f64::NAN,
None => f64::NAN,
};

self.acquisition_histogram
Expand Down
6 changes: 3 additions & 3 deletions flydra-types/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -859,8 +859,8 @@ impl Sorted {
Sorted(vals)
}
fn dist_and_argmin(&self, x: f64) -> (f64, usize) {
let mut best_dist = std::f64::INFINITY;
let mut prev_dist = std::f64::INFINITY;
let mut best_dist = f64::INFINITY;
let mut prev_dist = f64::INFINITY;
let mut best_idx = 0;
for (i, selfi) in self.0.iter().enumerate() {
let dist = (selfi - x).abs();
Expand Down Expand Up @@ -1358,7 +1358,7 @@ where
// TODO: should match on DeserializeError with empty field only,
// otherwise, return error. The way this is written, anything
// will return a nan.
Ok(std::f64::NAN),
Ok(f64::NAN),
)
}

Expand Down
2 changes: 1 addition & 1 deletion flydra-types/src/timestamp.rs
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ pub fn triggerbox_time(
#[test]
#[should_panic]
fn test_nan_handling() {
let _ts = FlydraFloatTimestampLocal::<Triggerbox>::from_f64(std::f64::NAN);
let _ts = FlydraFloatTimestampLocal::<Triggerbox>::from_f64(f64::NAN);
}

/// Ensure that conversion with particular floating point representation remains
Expand Down
2 changes: 1 addition & 1 deletion flydra-types/src/timestamp_opt_f64.rs
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ where
{
let val = match orig {
Some(ref tl) => tl.as_f64(),
None => std::f64::NAN,
None => f64::NAN,
};
serializer.serialize_f64(val)
}
Expand Down
10 changes: 2 additions & 8 deletions flydra2/src/connected_camera_manager.rs
Original file line number Diff line number Diff line change
Expand Up @@ -347,7 +347,7 @@ impl ConnectedCamerasManager {
inner.ccis.insert(
raw_cam_name.clone(),
ConnectedCameraInfo {
cam_num: cam_num.clone(),
cam_num,
raw_cam_name: raw_cam_name.clone(),
sync_state: ConnectedCameraSyncState::Unsynchronized,
http_camserver_info: http_camserver_info.clone(),
Expand Down Expand Up @@ -389,13 +389,7 @@ impl ConnectedCamerasManager {
TriggerType::FakeSync(_) => {
self.got_new_frame_live_triggerbox(packet, sync_pulse_pause_started_arc, 0)
}
TriggerType::PtpSync(ptpcfg) => {
if let Some(sync_data) = self.got_new_frame_live_ptp(packet, ptpcfg) {
sync_data
} else {
return None;
}
}
TriggerType::PtpSync(ptpcfg) => self.got_new_frame_live_ptp(packet, ptpcfg)?,
TriggerType::DeviceTimestamp => {
todo!();
}
Expand Down
Loading

0 comments on commit 25ded6d

Please sign in to comment.