Skip to content

Conversation

@corot
Copy link
Contributor

@corot corot commented Nov 11, 2017

As explained in this ROS answer, the 10Hz at witch STDR publishes odom and sensors TFs causes important delays when processing sensor readings. So solution has two parts:

  • Broadcast sensor tfs as static (though this will probably require changes on PR Added sensor pose read & write services #201 to republish the static tf if pose changes). This is already a good thing by itself, as it reduces simulation cost.
  • Allow speeding up odom tf (and odom topic) with a parameter odometry_rate

corot added a commit to corot/thorp that referenced this pull request Nov 11, 2017
Copy link
Member

@czalidis czalidis 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 your PR. I went ahead and created a review with some minor comments. It generally looks good; we would need to make some changes in the future to address the use case of a moving sensor (proposed by #201), but this is not in the scope of the current PR.

tf::TransformBroadcaster _tfBroadcaster;

//!< ROS tf2 static transform broadcaster
tf2_ros::StaticTransformBroadcaster static_broadcaster;
Copy link
Member

Choose a reason for hiding this comment

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

Prepend underscore to comply with the coding styleguide (I know it's ugly...).

Copy link
Contributor Author

Choose a reason for hiding this comment

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

right

//we should not start the timer, until we have a motion controller
_tfTimer = n.createTimer(
ros::Duration(0.1), &Robot::publishTransforms, this, false, false);
ros::Duration(1.0/odometry_rate), &Robot::publishTransforms, this, false, false);
Copy link
Member

@czalidis czalidis Nov 13, 2017

Choose a reason for hiding this comment

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

Could we put the default to 100Hz and not use the parameter? If you use the parameter you would need to check for division by zero. I also don't know what would be the computational impact if we increase to 100Hz though...

Copy link
Contributor Author

@corot corot Nov 13, 2017

Choose a reason for hiding this comment

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

Impact is small, I get similar same CPU usage (~85% vs. ~90% in my machine). What is normal as the function is quite light. But 50 Hz would be equally fine.

getName(),
_sensors[i]->getFrameId()));
}
_odomPublisher.publish(odom);
Copy link
Member

Choose a reason for hiding this comment

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

In this function the same time can be used when publishing odometry and the pose tf, instead of ros::Time::now() twice, in order to avoid the issue that you mentioned in your ROS Answer.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

true. In fact, using the same timestamp also for the sensors made things better (though using static tf is much much better anyway and the reasonable thing to do)

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