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

[JTC] Sample at t + dT instead of the beginning of the control cycle #1306

Open
wants to merge 10 commits into
base: master
Choose a base branch
from

Conversation

fmauch
Copy link
Contributor

@fmauch fmauch commented Oct 7, 2024

As mentioned in #1191 (comment) and discussed in #697 the JTC currently samples the trajectory at the time given to the update(time, period) method. However, this actually is the beginning of the control cycle and it would make more sense to sample the setpoint for the end of the control cycle, resulting in time + controller_update_period. This PR implements that.

I obviously had to update a couple of tests on the way, since with changing the sampling point, the resulting command can be significantly different.

Copy link

codecov bot commented Oct 7, 2024

Codecov Report

Attention: Patch coverage is 96.72131% with 2 lines in your changes missing coverage. Please review.

Project coverage is 80.38%. Comparing base (97c1e24) to head (c4022a2).

Files with missing lines Patch % Lines
...ory_controller/src/joint_trajectory_controller.cpp 71.42% 1 Missing and 1 partial ⚠️
Additional details and impacted files
@@            Coverage Diff             @@
##           master    #1306      +/-   ##
==========================================
+ Coverage   80.34%   80.38%   +0.03%     
==========================================
  Files         105      105              
  Lines        9384     9402      +18     
  Branches      826      829       +3     
==========================================
+ Hits         7540     7558      +18     
- Misses       1570     1571       +1     
+ Partials      274      273       -1     
Flag Coverage Δ
unittests 80.38% <96.72%> (+0.03%) ⬆️

Flags with carried forward coverage won't be shown. Click here to find out more.

Files with missing lines Coverage Δ
...jectory_controller/joint_trajectory_controller.hpp 100.00% <ø> (ø)
...ory_controller/test/test_trajectory_controller.cpp 99.74% <100.00%> (+<0.01%) ⬆️
...ntroller/test/test_trajectory_controller_utils.hpp 84.15% <100.00%> (ø)
...ory_controller/src/joint_trajectory_controller.cpp 83.67% <71.42%> (-0.18%) ⬇️

... and 2 files with indirect coverage changes

Copy link
Member

@saikishor saikishor left a comment

Choose a reason for hiding this comment

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

Look good. I've left some questions
I'll continue reviewing after we discuss this part.

Thanks for your great work @fmauch

Comment on lines 205 to +207
const bool valid_point = traj_external_point_ptr_->sample(
time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
time + update_period_, interpolation_method_, state_desired_, start_segment_itr,
end_segment_itr);
Copy link
Member

Choose a reason for hiding this comment

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

Above you are doing the initial sampling and immediately overriding with this future one. Is this intended?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Yes. The sample call above is - as the comment says - only to establish the actual start time of the trajectory. However, also in the first control cycle when we started the trajectory we want to sample at $t+\Delta t$ to generate the commands.

This should be probably refactored in the trajectory representation that the start time would not implicitly be specified by the first sample, but I thought this might not be the right PR to address that...

@@ -644,7 +646,7 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_not_angle_wraparoun
size_t n_joints = joint_names_.size();

// send msg
constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(250);
constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(300);
Copy link
Member

Choose a reason for hiding this comment

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

If the control period is 100 milliseconds, shouldn't it be 350?
Am i missing something here?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Why? Would it be desired to set a target time between two control cycles?

With a control period of 100 ms we would call update at $t_0 + 100ms, t_0 + 200ms, t_0+300ms$... So, in the update call at $t=t_0+200ms$ it should generate the command to reach the setpoint which is what we wait for below.

@fmauch fmauch requested a review from saikishor October 16, 2024 07:24
This isn't used anymore and more or less confusing, as actual will not
be desired as long as the robot is moving, which it is here.
@fmauch
Copy link
Contributor Author

fmauch commented Oct 16, 2024

The changes from ros-controls/ros2_control#1788 require revisiting the tests from this. I expect, that tests on the master branch will fail, as well, however, since I had to set correct rates all over the place within this PR.

Well, maybe not. I'll check this one, though.

Edit: Things are back to normal now.

Some tests require an update rate of 100 which isn't possible
if the default one is at 10.
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.

3 participants