-
Notifications
You must be signed in to change notification settings - Fork 9
Use rclcpp::Time for stamping transforms #20
Conversation
The motivation is that right now, `robot_state_publisher` doesn't respect `use_sim_time` at all.
nice. I won't have time to look at it before next week though. @chapulina could you give this a try and see if the laser update rate in RViz could be enhanced with it? THis might also be interesting for Karsten1987/confbot_robot#19 |
I don't think this will fix that issue, because I think @cottsay is still having the same issue even with this PR. |
FWIW, the changes here LGTM |
is this targeted for dashing or a patch release? |
This has missed the window for Dashing's initial release. |
@@ -99,6 +99,7 @@ class RobotStatePublisher | |||
std_msgs::msg::String model_xml_; | |||
bool description_published_; | |||
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr description_pub_; | |||
rclcpp::Clock::SharedPtr clock_; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
This breaks ABI by changing the size of RobotStatePublisher
. This is fine for Eloquent, but is an issue for including in a dashing patch release. This bug might be important enough to warrant breaking ABI.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
It probably makes sense to break ABI and release this to Dashing, see also #21.
* Use rclcpp::Time for stamping transforms The motivation is that right now, `robot_state_publisher` doesn't respect `use_sim_time` at all. * Use std::chrono constructor to represent 0.5 sec
* Use rclcpp::Time for stamping transforms The motivation is that right now, `robot_state_publisher` doesn't respect `use_sim_time` at all. * Use std::chrono constructor to represent 0.5 sec
The motivation is that right now,
robot_state_publisher
doesn't respectuse_sim_time
at all.