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

Create a transform subscribers to enable virtual joints #310

Merged
merged 17 commits into from
Aug 17, 2021

Conversation

JafarAbdi
Copy link
Member

Description

Fix: #261
Fix: #251

Checklist

  • Required by CI: Code is auto formatted using clang-format
  • Extend the tutorials / documentation reference
  • Document API changes relevant to the user in the MIGRATION.md notes
  • Create tests, which fail without this PR reference
  • Include a screenshot if changing a GUI
  • While waiting for someone to review your request, please help review another open pull request to support the maintainers

@codecov
Copy link

codecov bot commented Nov 18, 2020

Codecov Report

Merging #310 (578664e) into main (4f5bacd) will increase coverage by 0.14%.
The diff coverage is 81.58%.

Impacted file tree graph

@@            Coverage Diff             @@
##             main     #310      +/-   ##
==========================================
+ Coverage   53.98%   54.12%   +0.14%     
==========================================
  Files         190      190              
  Lines       20002    20034      +32     
==========================================
+ Hits        10796    10841      +45     
+ Misses       9206     9193      -13     
Impacted Files Coverage Δ
...eit/planning_scene_monitor/current_state_monitor.h 77.78% <ø> (ø)
...anning_scene_monitor/src/current_state_monitor.cpp 74.18% <72.00%> (+9.23%) ⬆️
...or/src/current_state_monitor_middleware_handle.cpp 85.72% <100.00%> (+12.39%) ⬆️

Continue to review full report at Codecov.

Legend - Click here to learn more
Δ = absolute <relative> (impact), ø = not affected, ? = missing data
Powered by Codecov. Last update 4f5bacd...578664e. Read the comment docs.

@@ -200,7 +200,6 @@ int main(int argc, char** argv)

std::shared_ptr<tf2_ros::Buffer> tf_buffer =
std::make_shared<tf2_ros::Buffer>(nh->get_clock(), tf2::durationFromSec(10.0));
std::shared_ptr<tf2_ros::TransformListener> tfl = std::make_shared<tf2_ros::TransformListener>(*tf_buffer);
Copy link
Member

Choose a reason for hiding this comment

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

We shouldn't rely on the CurrentStateMonitor to fill the tf_buffer. The TransformListener is required for the PlanningSceneMonitor to work without it.

Copy link
Contributor

Choose a reason for hiding this comment

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

I think this comment is obsolete now, since parallel functionality was implemented through subscribers on the /tf topic.

Copy link
Member

Choose a reason for hiding this comment

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

How is this comment obsolete? The subscribers are initialized inside the CSM so unless we call PSM::startStateMonitor() there won't be any listeners updating the buffer. A reasonable workaround would be to move the transform subscribers into the PSM and to call CSM::updateMultiDofJoints from there. What do you think?

Copy link
Member Author

@JafarAbdi JafarAbdi Aug 11, 2021

Choose a reason for hiding this comment

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

We do always call startStateMonitor when constructing move_group & moveit_cpp

@@ -61,7 +60,6 @@ MoveItCpp::MoveItCpp(const rclcpp::Node::SharedPtr& node, const Options& options
{
if (!tf_buffer_)
tf_buffer_ = std::make_shared<tf2_ros::Buffer>(node_->get_clock());
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
Copy link
Member

Choose a reason for hiding this comment

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

Here the same, we should run a TransformListener independent of the CSM.

Copy link
Contributor

Choose a reason for hiding this comment

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

Same with this comment.

Copy link
Member Author

Choose a reason for hiding this comment

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

See my previous comment

@henningkayser
Copy link
Member

I thought about this and I don't think we should merge this solution. We should have an independent TransformListener running at all times. If that's not possible, we might implement our own listener that supports callbacks.

@@ -200,7 +200,6 @@ int main(int argc, char** argv)

std::shared_ptr<tf2_ros::Buffer> tf_buffer =
std::make_shared<tf2_ros::Buffer>(nh->get_clock(), tf2::durationFromSec(10.0));
std::shared_ptr<tf2_ros::TransformListener> tfl = std::make_shared<tf2_ros::TransformListener>(*tf_buffer);
Copy link
Contributor

Choose a reason for hiding this comment

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

I think this comment is obsolete now, since parallel functionality was implemented through subscribers on the /tf topic.

@@ -61,7 +60,6 @@ MoveItCpp::MoveItCpp(const rclcpp::Node::SharedPtr& node, const Options& options
{
if (!tf_buffer_)
tf_buffer_ = std::make_shared<tf2_ros::Buffer>(node_->get_clock());
tf_listener_ = std::make_shared<tf2_ros::TransformListener>(*tf_buffer_);
Copy link
Contributor

Choose a reason for hiding this comment

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

Same with this comment.

@DLu
Copy link
Contributor

DLu commented May 4, 2021

@JafarAbdi Any thoughts on addressing @schornakj 's comments?

Copy link
Member

@henningkayser henningkayser left a comment

Choose a reason for hiding this comment

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

Sorry for letting the reviews pend for so long. I think this PR is really getting there but the original complaint doesn't seem to be fixed, which is that the PSM doesn't update TF if the CSM is not initialized (please correct me if I'm wrong). This could for instance break the planning scene display as that one doesn't listen for joint states explicitly. The callback implementation looks good to me on its own (argree, no class required) but please consider moving them into the PSM and updating the transforms from there (see comment).

transform.child_frame_id.c_str(), transform.header.frame_id.c_str(), temp.c_str());
}
}
updateMultiDofJoints();
Copy link
Member

Choose a reason for hiding this comment

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

isn't this redundant in case of a transform exception?

Copy link
Member Author

Choose a reason for hiding this comment

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

What if the exception happened after adding few transforms to the buffer .?

@@ -200,7 +200,6 @@ int main(int argc, char** argv)

std::shared_ptr<tf2_ros::Buffer> tf_buffer =
std::make_shared<tf2_ros::Buffer>(nh->get_clock(), tf2::durationFromSec(10.0));
std::shared_ptr<tf2_ros::TransformListener> tfl = std::make_shared<tf2_ros::TransformListener>(*tf_buffer);
Copy link
Member

Choose a reason for hiding this comment

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

How is this comment obsolete? The subscribers are initialized inside the CSM so unless we call PSM::startStateMonitor() there won't be any listeners updating the buffer. A reasonable workaround would be to move the transform subscribers into the PSM and to call CSM::updateMultiDofJoints from there. What do you think?

@JafarAbdi JafarAbdi force-pushed the pr-virtual_joints branch 2 times, most recently from 0eb4492 to 16814bb Compare July 29, 2021 15:23
@JafarAbdi JafarAbdi force-pushed the pr-virtual_joints branch 2 times, most recently from a0b6b0c to 9f3be3e Compare August 11, 2021 22:55
@JafarAbdi
Copy link
Member Author

I think this PR is ready to be merged, regarding having an independent transform listener for PSM I didn't change the behavior from ROS1, the user have to provide it themselves unless a current state monitor is also enabled in that case a warning message will be print telling that the transforms will be added by both transform listener & current state monitor's callbacks

@@ -401,8 +408,11 @@ void CurrentStateMonitor::tfCallback()
continue;
}

if (auto joint_time_it = joint_time_.find(joint); joint_time_it == joint_time_.end())
joint_time_.emplace(joint, rclcpp::Time(0, 0, RCL_ROS_TIME));

// allow update if time is more recent or if it is a static transform (time = 0)
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
// allow update if time is more recent or if it is a static transform (time = 0)
// skip if time is not more recent and is not a static transform (time = 0)

Comments should use the same logic as the conditionals, don't make the person parsing it invert conditions.

JafarAbdi and others added 2 commits August 13, 2021 23:24
…onitor.cpp

Co-authored-by: Nathan Brooks <nbbrooks@gmail.com>
…onitor.cpp

Co-authored-by: Nathan Brooks <nbbrooks@gmail.com>
Copy link
Member

@henningkayser henningkayser left a comment

Choose a reason for hiding this comment

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

LGTM! Also, thanks for the tests @JafarAbdi. This fix is good for now, but I think this PR exposes serious flaws in the PSM API that should be addressed.

Using an external TF listener is discouraged now in case CSM is used since transforms callbacks would be duplicate. This should be documented and ideally checked for inside the PSM constructor. If the CSM is not used, an external listener is strictly required to keep transforms updated. For the PSM it means that it's highly questionable if tf_buffer receives updated transforms or not. Obviously, some of this confusion was already present in ROS 1, but this PR makes it just a little bit more confusing.

One way to guarantee that PSM has a valid listener would be to:

  • Remove/Deprecate tf_buffer from PSM constructors
  • Initialize a private tf_listener inside PSM, possibly using startTFListener() to make this optional
  • Stop tf_listener with startStateMonitor(), restart it with stopStateMonitor()

(this is definitely out of scope of this PR)

Copy link
Member

@tylerjw tylerjw left a comment

Choose a reason for hiding this comment

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

Thank you for adding this. I generally agree with Henning that this part of the code needs a closer look to make the correct use of the API more obvious.

@JafarAbdi JafarAbdi merged commit 974a7a1 into moveit:main Aug 17, 2021
@JafarAbdi JafarAbdi deleted the pr-virtual_joints branch August 17, 2021 19:37
tylerjw pushed a commit to tylerjw/moveit2 that referenced this pull request Aug 27, 2021
MikeWrock pushed a commit to MikeWrock/moveit2 that referenced this pull request Aug 15, 2022
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.

Support virtual joints in CurrentStateMonitor Planning for a mobile robot
6 participants