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

feat: set timestamp to max_velocity topic #125

Merged
merged 2 commits into from
Aug 21, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -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_;

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
@@ -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>(
@@ -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);
}
}