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

Refactoring: Splitting periodicUpdate method into smaller methods #761

Open
wants to merge 3 commits into
base: humble-devel
Choose a base branch
from

Conversation

firemark
Copy link
Contributor

Because method RosFilter::periodicUpdate is a big method, I cut into smaller methods.

In some methods (validateFilterOutput, getFilteredAccelMessage and getFilteredOdometryMessage) I changed an argument type from pointer to reference, because a pointer could be dangerous.

src/ros_filter.cpp Outdated Show resolved Hide resolved
Copy link
Collaborator

@ayrton04 ayrton04 left a comment

Choose a reason for hiding this comment

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

Generally looks good, thanks. Just some smaller requests.

@@ -199,14 +199,14 @@ class RosFilter : public rclcpp::Node
//! @param[out] message - The standard ROS odometry message to be filled
//! @return true if the filter is initialized, false otherwise
//!
bool getFilteredOdometryMessage(nav_msgs::msg::Odometry * message);
bool getFilteredOdometryMessage(nav_msgs::msg::Odometry & message);
Copy link
Collaborator

Choose a reason for hiding this comment

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

I am struggling to find it, but at some point, there was definitely a document that suggested that in ROS 2, passing parameters as pointers was preferred. Was there a reason for this change? I'm not against it - I prefer reference parameters - but I am trying to determine if this was required for some reason, or you were just looking to be consistent.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Raw pointers are more dangerous than references - pointer could be a NULL or contains wrong address, so it requires more guards in the method (e.g. https://pvs-studio.com/en/docs/warnings/v595/). So only reason is reference is safer because a compiler guards the argument.

I am struggling to find it, but at some point, there was definitely a document that suggested that in ROS

Unfortunately I didn't find that - but I found:

These links are not related with this comment but they could help with subscriptions in the future :)

Anyway I see, the best way is use std::optional instead of reference and returning bool. Could you review my next commit?

//! getFilteredOdometryMessage.
//! @return true if data is corrected otherwise false.
//!
bool publishPositionWithOdometry(nav_msgs::msg::Odometry filtered_position);
Copy link
Collaborator

Choose a reason for hiding this comment

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

If we're sticking with reference types, is there any reason this isn't const ref?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Half year ago I'm was experimenting with std::move() and it was bad.

I have changed the argument to const ref.

//!
void updateFilterWithMeasurements(const rclcpp::Time & time);

//! @brief publish world to base link transform and position
Copy link
Collaborator

Choose a reason for hiding this comment

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

Would this go over 100 characters without the line break?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Yep. Fixed.

{
nav_msgs::msg::Odometry filtered_position;
if (getFilteredOdometryMessage(filtered_position)) {
corrected_data = publishPositionWithOdometry(std::move(filtered_position));
Copy link
Collaborator

Choose a reason for hiding this comment

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

If you make this method take a const ref, there's no need for the std::move. Not sure what that does in the context of a value parameter anyway.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Fixed.

}

if (frame_id != map_frame_id_) {
std::cerr << "Odometry message frame_id was " <<
Copy link
Collaborator

Choose a reason for hiding this comment

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

As long as you're here, you can replace any cerr statements with the actual ROS 2 logging macros, and uncomment/update the ROS 1 macros further down.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Fixed.

@firemark firemark force-pushed the periodic-update-refactoring branch from 1622b3d to 3d8534a Compare January 25, 2023 16:32
@firemark firemark requested a review from ayrton04 January 26, 2023 14:14
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