Implementation of model_delay with dynamic parameter#6066
Implementation of model_delay with dynamic parameter#6066BriceRenaudeau wants to merge 1 commit intoros-navigation:mainfrom
Conversation
| } | ||
|
|
||
| // Apply model delay | ||
| if(model_delay_ == 0.0) {return;} |
There was a problem hiding this comment.
Would it make sense if less than model_dt_ to skip? Or I suppose by the current math < 0.5 * model_dt_ would be the same since the offset would be floored to 0 in which case.
But more architecturally, if hte offset is less than one cycle's DT, does it make sense to apply any lag?
| auto state_copy = state; | ||
| for (unsigned int i = 0; i != state.vx.shape(0); i++) { | ||
| for (unsigned int j = 1; j != state.vx.shape(1); j++) { | ||
| // Keep the first value before delay (because we cannot do better) |
There was a problem hiding this comment.
| // Keep the first value before delay (because we cannot do better) | |
| // Keep the first values before delay |
Making plural in case large.
| unsigned int offset = std::floor((model_delay_ / model_dt_) + 0.5); | ||
| auto state_copy = state; | ||
| for (unsigned int i = 0; i != state.vx.shape(0); i++) { | ||
| for (unsigned int j = 1; j != state.vx.shape(1); j++) { |
There was a problem hiding this comment.
I'll probably take care of this for you but leaving a note for myself: These loops may be eigenized for vectorized operations.
|
Thanks for this. Briefly, did you look at huynhduc9905#6 which implemented a first-order lag model? Is there any of this that you'd like / think we should use (or a different strategy and what you did is better)? I believe the intention is to estimate the lag at run-time versus a parameterization. |
There was a problem hiding this comment.
Usual bits on adding the param to the configuration guide + mention this in the migration guide (though looks like this has some compilation issues).
I know that this is a patch you've built that fixed an issue for you, so if you need me to drive it home with fixing things up with the current version of MPPI, I can do that. I'd just ask that you test to make sure that this works still for your needs & answer my questions above.
Also note this comment: #6065 (comment)
Basic Info
@SteveMacenski and @doisyg , here is a small implementation of our talk long ago.
Description of contribution in a few bullet points
model_delayDescription of how this change was tested
Future work that may be required in bullet points
For Maintainers:
backport-*.