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

New functionality to transform PoseWithCovarianceStamped messages. #282

Merged
merged 2 commits into from
Feb 8, 2018
Merged

New functionality to transform PoseWithCovarianceStamped messages. #282

merged 2 commits into from
Feb 8, 2018

Conversation

RobertBlakeAnderson
Copy link
Contributor

New functions added which handle the spatial transformation of a geometry_msgs::PoseWithCovarianceStamped message. The transformation mutates the covariance matrix as well as the pose.

Copy link
Member

@tfoote tfoote left a comment

Choose a reason for hiding this comment

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

Thanks for submitting this. I had a few requests but overall it looks like a good thing to add.

@@ -161,7 +199,8 @@ int main(int argc, char **argv){
ros::NodeHandle n;

tf_buffer = new tf2_ros::Buffer();

tf_buffer->setUsingDedicatedThread(true);
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 have to change this?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

When running the tests on my machine, I was getting many instances of this error:

[ERROR] [1518043130.234301067]: Do not call canTransform or lookupTransform with a timeout unless you are using another thread for populating data. Without a dedicated thread it will always timeout. If you have a seperate thread servicing tf messages, call setUsingDedicatedThread(true) on your Buffer instance.

Adding this line eliminated the errors.

Copy link
Member

Choose a reason for hiding this comment

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

It's not "correct" but if it suppresses the warnings/errors for the test console output that's probably better for readability.

* \param transform The timestamped transform to apply, as a TransformStamped message.
* \return The transformed covariance matrix.
*/
geometry_msgs::PoseWithCovariance::_covariance_type transformCovariance(const geometry_msgs::PoseWithCovariance::_covariance_type& cov_in, const tf2::Transform& transform)
Copy link
Member

Choose a reason for hiding this comment

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

inline missing here

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Will fix.

v1.pose.covariance[35] = 1;

// simple api
const geometry_msgs::PoseWithCovarianceStamped v_simple = tf_buffer->transform(v1, "B", ros::Duration(2.0));
Copy link
Member

Choose a reason for hiding this comment

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

Can you add some basic checks of the covariance values? That's a core part of this and there's no coverage of it in these tests.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Sure thing.

Copy link
Contributor Author

@RobertBlakeAnderson RobertBlakeAnderson Feb 7, 2018

Choose a reason for hiding this comment

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

Actually, just realized the transform t used in all these tests performs no rotations. I'll need to declare a local tf_ros::Buffer and Transform for my test to do a rotation on the covariance matrix.

Copy link
Member

@tfoote tfoote left a comment

Choose a reason for hiding this comment

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

Sorry wrong button

2. Incorporated comments from tfoote.
3. Added testing of covariance rotation.
@RobertBlakeAnderson
Copy link
Contributor Author

Updated for requested changes. Testing the covariance transformation did reveal a bug, so good call there.

@tfoote
Copy link
Member

tfoote commented Feb 8, 2018

@ros-pull-request-builder retest this please

@RobertBlakeAnderson
Copy link
Contributor Author

Looks like the failure is due to a canTransform call timing out in the tf2_ros tests. It passes if I run the tf2_ros tests alone on my machine though.

@tfoote
Copy link
Member

tfoote commented Feb 8, 2018

Yes those are known flakey tests. See #129, I just tried to resolve them again in #283.

Copy link
Member

@tfoote tfoote left a comment

Choose a reason for hiding this comment

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

Thanks for the update and basic tests.

@@ -161,7 +199,8 @@ int main(int argc, char **argv){
ros::NodeHandle n;

tf_buffer = new tf2_ros::Buffer();

tf_buffer->setUsingDedicatedThread(true);
Copy link
Member

Choose a reason for hiding this comment

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

It's not "correct" but if it suppresses the warnings/errors for the test console output that's probably better for readability.

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.

2 participants