Skip to content

Commit

Permalink
feat: set timestamp to max_velocity topic (#125)
Browse files Browse the repository at this point in the history
* set timestamp to max_velocity topic

Signed-off-by: Autumn60 <[email protected]>

* fix constructor order

Signed-off-by: Autumn60 <[email protected]>

---------

Signed-off-by: Autumn60 <[email protected]>
  • Loading branch information
Autumn60 authored Aug 21, 2024
1 parent d409b66 commit 5effcb8
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@ class AutowareIvMaxVelocityPublisher
void statePublisher(const AutowareInfo & aw_info);

private:
rclcpp::Clock::SharedPtr clock_;

// publisher
rclcpp::Publisher<tier4_planning_msgs::msg::VelocityLimit>::SharedPtr pub_state_;

Expand Down
3 changes: 2 additions & 1 deletion awapi_awiv_adapter/src/awapi_max_velocity_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ namespace autoware_api
{
AutowareIvMaxVelocityPublisher::AutowareIvMaxVelocityPublisher(
rclcpp::Node & node, const double default_max_velocity)
: default_max_velocity_(default_max_velocity)
: clock_(node.get_clock()), default_max_velocity_(default_max_velocity)
{
// publisher
pub_state_ = node.create_publisher<tier4_planning_msgs::msg::VelocityLimit>(
Expand All @@ -32,6 +32,7 @@ void AutowareIvMaxVelocityPublisher::statePublisher(const AutowareInfo & aw_info
aw_info.max_velocity_ptr, aw_info.temporary_stop_ptr,
&max_velocity.max_velocity)) // publish info
{
max_velocity.stamp = clock_->now();
pub_state_->publish(max_velocity);
}
}
Expand Down

0 comments on commit 5effcb8

Please sign in to comment.