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

Resolve premature controller initialization #213

Conversation

miguelprada
Copy link
Contributor

In my (admittedly limited) tests this resolves #206.

It partially reverts the changes in Zagitta#6, in particular the code that ensures the controllers are updated at a minimum rate of 125Hz.

@miguelprada
Copy link
Contributor Author

I reverted the original commit in this PR and replaced it with a different solution to the issue. It basically avoids calling ControllerManager::update (and therefore avoids starting controllers) until at least one RTPacket has been received.

Feel free to squash merge if you're happy with the final result.

Copy link

@v4hn v4hn left a comment

Choose a reason for hiding this comment

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

one nitpick, otherwise this looks good to me.

src/ros/controller.cpp Outdated Show resolved Hide resolved
@AndyZe
Copy link

AndyZe commented Oct 25, 2018

Works great for me.

@miguelprada
Copy link
Contributor Author

Ping @gavanderhoorn, @ipa-nhg. Any chance you can review this?

Not sure why the tests are marked yellow here, since they show as passed in Travis CI.

@gavanderhoorn
Copy link
Member

I've restarted the build.

Travis can be a bit strange sometimes.

@gavanderhoorn
Copy link
Member

@miguelprada: this seems like it should fix running controllers without knowing the current state of the robot, but may I suggest we change it for readability to check state_initialized_ in ROSController::update()?

So something like:

bool ROSController::update()
{
  // don't run controllers if we haven't received robot state yet
  if (!state_initialized_)
    return;

  ...
}

I'm assuming the compiler will in-line the call to ROSController::update() in ROSController::onTimeout() (with #225, if it isn't doing it already), so the unconditional call to ROSController::update() should not really matter.

Copy link
Member

@gavanderhoorn gavanderhoorn left a comment

Choose a reason for hiding this comment

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

I would suggest using robot_state_received_ as the name for the variable. state_initialized_ is too generic and doesn't convey the fact that the variable really captures whether the driver has received the initial state from the robot.

include/ur_modern_driver/ros/controller.h Outdated Show resolved Hide resolved
src/ros/controller.cpp Outdated Show resolved Hide resolved
src/ros/controller.cpp Outdated Show resolved Hide resolved
src/ros/controller.cpp Outdated Show resolved Hide resolved
- Renames state_initialized_ as robot_state_received_
- Relocates the check into ROSController::update
@miguelprada
Copy link
Contributor Author

I believe all requests have been fulfilled.

@gavanderhoorn gavanderhoorn merged commit 2f1251c into ros-industrial-attic:kinetic-devel Nov 5, 2018
@gavanderhoorn
Copy link
Member

Thanks @miguelprada for the fix and for iterating on it with me. 👍

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.

4 participants