Skip to content

Commit

Permalink
fix(ndt_scan_matcher): changed the type of timestamp from double to i…
Browse files Browse the repository at this point in the history
…nt in ndt diag (autowarefoundation#7128)

Changed the type of timestamp from double to int in ndt diag

Signed-off-by: Shintaro Sakoda <shintaro.sakoda@tier4.jp>
  • Loading branch information
SakodaShintaro authored and a-maumau committed Jun 7, 2024
1 parent a882d30 commit f4be9d7
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 6 deletions.
2 changes: 1 addition & 1 deletion localization/ndt_scan_matcher/src/map_update_module.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ void MapUpdateModule::callback_timer(
const bool is_activated, const std::optional<geometry_msgs::msg::Point> & position,
std::unique_ptr<DiagnosticsModule> & diagnostics_ptr)
{
diagnostics_ptr->addKeyValue("timer_callback_time_stamp", clock_->now().seconds());
diagnostics_ptr->addKeyValue("timer_callback_time_stamp", clock_->now().nanoseconds());

// check is_activated
diagnostics_ptr->addKeyValue("is_activated", is_activated);
Expand Down
11 changes: 6 additions & 5 deletions localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,7 +214,8 @@ void NDTScanMatcher::callback_initial_pose_main(
const geometry_msgs::msg::PoseWithCovarianceStamped::ConstSharedPtr initial_pose_msg_ptr)
{
diagnostics_initial_pose_->addKeyValue(
"topic_time_stamp", static_cast<rclcpp::Time>(initial_pose_msg_ptr->header.stamp).seconds());
"topic_time_stamp",
static_cast<rclcpp::Time>(initial_pose_msg_ptr->header.stamp).nanoseconds());

// check is_activated
diagnostics_initial_pose_->addKeyValue("is_activated", static_cast<bool>(is_activated_));
Expand Down Expand Up @@ -255,7 +256,7 @@ void NDTScanMatcher::callback_regularization_pose(
diagnostics_regularization_pose_->clear();

diagnostics_regularization_pose_->addKeyValue(
"topic_time_stamp", static_cast<rclcpp::Time>(pose_conv_msg_ptr->header.stamp).seconds());
"topic_time_stamp", static_cast<rclcpp::Time>(pose_conv_msg_ptr->header.stamp).nanoseconds());

regularization_pose_buffer_->push_back(pose_conv_msg_ptr);

Expand Down Expand Up @@ -295,7 +296,7 @@ bool NDTScanMatcher::callback_sensor_points_main(

// check topic_time_stamp
const rclcpp::Time sensor_ros_time = sensor_points_msg_in_sensor_frame->header.stamp;
diagnostics_scan_points_->addKeyValue("topic_time_stamp", sensor_ros_time.seconds());
diagnostics_scan_points_->addKeyValue("topic_time_stamp", sensor_ros_time.nanoseconds());

// check sensor_points_size
const size_t sensor_points_size = sensor_points_msg_in_sensor_frame->width;
Expand Down Expand Up @@ -867,7 +868,7 @@ void NDTScanMatcher::service_trigger_node(
std_srvs::srv::SetBool::Response::SharedPtr res)
{
diagnostics_trigger_node_->clear();
diagnostics_trigger_node_->addKeyValue("service_call_time_stamp", this->now().seconds());
diagnostics_trigger_node_->addKeyValue("service_call_time_stamp", this->now().nanoseconds());

is_activated_ = req->data;
if (is_activated_) {
Expand Down Expand Up @@ -905,7 +906,7 @@ void NDTScanMatcher::service_ndt_align_main(
const tier4_localization_msgs::srv::PoseWithCovarianceStamped::Request::SharedPtr req,
tier4_localization_msgs::srv::PoseWithCovarianceStamped::Response::SharedPtr res)
{
diagnostics_ndt_align_->addKeyValue("service_call_time_stamp", this->now().seconds());
diagnostics_ndt_align_->addKeyValue("service_call_time_stamp", this->now().nanoseconds());

// get TF from pose_frame to map_frame
const std::string & target_frame = param_.frame.map_frame;
Expand Down

0 comments on commit f4be9d7

Please sign in to comment.