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

add configurable homing timeout #442

Open
wants to merge 1 commit into
base: melodic-devel
Choose a base branch
from

Conversation

sgermanserrano
Copy link

Enables to have a configurable homing timeout for slower joints, e.g.

defaults: # optional, all defaults can be overwritten per node
  eds_pkg: my_config_package # optional package  name for relative path
  eds_file: "my_config.dcf" # path to EDS/DCF file
  motor_layer:
    homing_timeout: 60
  dcf_overlay: # "ObjectID": "ParameterValue" (both as strings)
    "1016sub1" : "0x7F0064" # heartbeat timeout of 100 ms for master at 127
    "1017": "100" # heartbeat producer

It defaults to 10s to keep the original behaviour

Signed-off-by: Servando German Serrano servando.german.serrano@gmail.com

Copy link
Member

@mathias-luedtke mathias-luedtke left a comment

Choose a reason for hiding this comment

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

Thanks! I had a similar patch in mind. Right now I am just not sure, if we should break the ABI like this.

@@ -504,6 +508,8 @@ void Motor402::handleInit(LayerStatus &status){
return;
}

homing->setHomingTimeout(homing_timeout_);
Copy link
Member

Choose a reason for hiding this comment

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

Why did you create a new function and did not pass it as a parameter to executeHoming?

Copy link
Author

Choose a reason for hiding this comment

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

@ipa-mdl tbh, I didn't know which option was better, I'll refactor to have it as:
executeHoming(canopen::LayerStatus &status, const boost::chrono::seconds &homing_timeout)
and pass it with the call to executeHoming

Copy link
Member

Choose a reason for hiding this comment

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

Me neither ;)

That's why I wanted to know why you chose that option.

I'll refactor to have it as:
executeHoming(canopen::LayerStatus &status, const boost::chrono::seconds &homing_timeout)
and pass it with the call to executeHoming

👍

Please keep the function without the argument as well (stable API) and call the new one with a timeout of 10s (as before).
I will try to figure out, if we can avoid the ABI break in Motor402.

Copy link
Author

Choose a reason for hiding this comment

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

I've added the new function and replace the call to executeHoming with a default timeout of 10s

Signed-off-by: Servando German Serrano <servando.german.serrano@gmail.com>
@ivan140
Copy link

ivan140 commented Dec 17, 2021

Any updates or help needed on this pull request? I've tested it on a super slow joint and the homing was working really good, so looking forward for a merge :)

@amilcarlucas
Copy link

Ping. Please merge

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.

None yet

4 participants