Skip to content
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

New: Calculate elapsed time in ctrl_loop #92

Merged
merged 1 commit into from
Nov 29, 2022

Conversation

matthias-mayr
Copy link
Contributor

  • ros_control expects the actual time difference in the update call
  • I did not use the actually measured time in safety checks and velocity calculation yet. I was not brave enough to enable that. Also if there are FRI interruptions, this value can become seconds.
  • ros::Time::now() is not realtime safe. However realtime_tools' clock limited to 750Hz right now: Hard coded loop rate ros-controls/realtime_tools#23

Here are some measurements of the elapsed time (wrongly labelled "ctrl_duration" in the plot) running a 1 kHz FRI connection (#90) together with this Cartesian impedance controller:
image
(Green and blue (covered by green) are the controller calculations)

- ros_control expects the actual time difference
- Did not use the actually measured time in safety checks and vel. calculation yet
- ros::Time::now() is not realtime safe. However realtime_tools' clock limited to 750Hz right now:
  ros-controls/realtime_tools#23
Copy link
Collaborator

@costashatz costashatz left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thanks for another PR. :)

@@ -321,23 +322,23 @@ namespace iiwa_ros {

for (int i = 0; i < _num_joints; i++) {
_joint_position[i] = _robot_state.getMeasuredJointPosition()[i];
_joint_velocity[i] = filters::exponentialSmoothing((_joint_position[i] - _joint_position_prev[i]) / elapsed_time.toSec(), _joint_velocity[i], 0.2);
_joint_velocity[i] = filters::exponentialSmoothing((_joint_position[i] - _joint_position_prev[i]) / ctrl_duration.toSec(), _joint_velocity[i], 0.2);
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why not elapsed_time here? I guess you have good reasons, but I'd like to have them documented.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

well, one of them is that we should handle interruptions then. That leads to very large values for the measured elapsed time. Like seconds.

The second reason is that when we implemented the controller for the IROS 2021 paper, you told me that we should not use the actual time when integrating, but only the expected time. I applied the same reasoning on the derivative here.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good enough! Merging... Thanks again! :)

@costashatz costashatz merged commit cd49fdb into epfl-lasa:master Nov 29, 2022
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants