Skip to content

Commit 823934d

Browse files
committed
keep the joint state for known joints on reload
1 parent 576fe10 commit 823934d

1 file changed

Lines changed: 22 additions & 1 deletion

File tree

src/app.rs

Lines changed: 22 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -345,10 +345,31 @@ impl UrdfViewerApp {
345345
self.remove_frame_markers(window);
346346
// update urdf_robot
347347
reload_fn(&mut self.urdf_robot);
348-
349348
// update robot based on new urdf_robot
350349
let urdf_robot = self.urdf_robot.get();
350+
351+
let previous_positions: HashMap<_, _> = self
352+
.robot
353+
.iter_joints()
354+
.map(|j| (j.name.clone(), j.joint_position().unwrap()))
355+
.collect();
351356
self.robot = urdf_robot.into();
357+
358+
// restore joint positions
359+
let joint_positions: Vec<_> = self
360+
.robot
361+
.iter_joints()
362+
.map(|j| {
363+
previous_positions
364+
.get(&j.name)
365+
.copied()
366+
.unwrap_or(j.joint_position().unwrap())
367+
})
368+
.collect();
369+
self.robot
370+
.set_joint_positions(&joint_positions)
371+
.unwrap_or(());
372+
352373
self.input_path = PathBuf::from(&self.urdf_robot.path);
353374
let end_link_names = if self.input_end_link_names.is_empty() {
354375
self.robot

0 commit comments

Comments
 (0)