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

Meeting ROS-I specs #46

Merged
merged 27 commits into from
Oct 11, 2016
Merged

Meeting ROS-I specs #46

merged 27 commits into from
Oct 11, 2016

Conversation

carlosjoserg
Copy link
Collaborator

@carlosjoserg carlosjoserg commented Aug 6, 2015

This PR contains changes according to ROS-I specs:

  • [lwr_hw] nodes now use CLOCK_MONOTONIC time.
  • [lwr_description] joint names match the kuka names
  • [lwr_description] clean up in the meshes folder

ToDo:

  • Resolve Implement low-level software stop using ROS topic for all interfaces #44
    Note: Once we have all interfaces in master then we can do this in a different PR
  • Resolve Moveit planning execution #23 .. working on this now.
  • Fix the visual geometries
    Note: I don't think we will find better geometries... the current ones do not actually match perfectly the real ones, but I think we can live with that.
  • Port format 2.0 of package.xml's to match the real one
  • Eliminate KUKA protected files from history and replace default interface with Stanford FRIL (URGENT)
    Note: This has to be worked in a different PR that tackles the Stanford FRIL iface.

@carlosjoserg
Copy link
Collaborator Author

Ok, probably I won't be able to tackle all the list above in this PR... but let's see where it can get.

@carlosjoserg
Copy link
Collaborator Author

Rebased, merged, etc... waiting for travis...

carlosjoserg and others added 23 commits October 10, 2016 17:51
…sual.

The lwr4plus/collision folder is created, but recall that in this package the collision geometry is formed of basic primitives within the urdf model.
… controllers now are updated at a fixed sampling rate defined in the script being used in the robot
Most likely, I will discard the different pre-configured modes I had in
mind, and leave the kuka ones:
joint position = 10
cartesian impedance = 20
joint impedance =
 30
@carlosjoserg
Copy link
Collaborator Author

Finally, this is ready to merge...

This PR contains a lot of changes, so I'll leave it open one more day in case someone has something to say, and I'll merge tomorrow morning otherwise.

@carlosjoserg
Copy link
Collaborator Author

And I'm going to add the pending items from the list above as issues.

Copy link
Collaborator

@miguelprada miguelprada left a comment

Choose a reason for hiding this comment

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

Other than the timing issues, I see no problem with the rest.

//the controller manager
controller_manager::ControllerManager manager(&lwr_robot, lwr_nh);

// run as fast as possible
while( !g_quit )
{
// get the time / period
if (!clock_gettime(CLOCK_REALTIME, &ts))
if (!clock_gettime(CLOCK_MONOTONIC, &ts))
Copy link
Collaborator

@miguelprada miguelprada Oct 11, 2016

Choose a reason for hiding this comment

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

Using CLOCK_MONOTONIC to set the current time in the call to update has caused some issues in other packages before (e.g. scheduling trajectories far into the future by the joint trajectory controller, publishing messages with timestamps incompatible with other ROS nodes). See conversation from this comment.

Both the ur_modern_driver and the ros_control_boilerplate have settled on using the monotonic clock to compute the elapsed time, but setting the current time using ros::Time::now().

Copy link
Collaborator Author

Choose a reason for hiding this comment

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

I see... just reading all discussions, jumping from issue to issue in a wikipedia navigation style.

I've never experienced any issue here though, but good to have this in the background just in case.

Thanks for the review ;)

@@ -99,7 +99,7 @@ int main( int argc, char** argv )
while( !g_quit )
{
// get the time / period
if (!clock_gettime(CLOCK_REALTIME, &ts))
if (!clock_gettime(CLOCK_MONOTONIC, &ts))
Copy link
Collaborator

Choose a reason for hiding this comment

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

Idem.

@carlosjoserg carlosjoserg merged commit 7af96bd into master Oct 11, 2016
@carlosjoserg carlosjoserg deleted the ros-i-specs branch October 11, 2016 09:59
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