Skip to content

Filtered times are offset from sensor times. #184

@HansLarsen

Description

@HansLarsen

The filtered times are offset and stuck in a 1 second interval loop.
TIMESTAMPS
Heres plot juggler, the red line is the input laser scans and the orange line is the output from the filter.

I'm on commit 65cbefd
The distribution is ROS2 humble, everything build from the latest sources, according to the build from source guide, on Ubuntu 18.04.

The delay is likewise present if you print them in the callback:

Callback
  void callback(const std::shared_ptr<const sensor_msgs::msg::LaserScan> & msg_in)
  {
    RCLCPP_INFO(
      nh_->get_logger(), "%d, %d", msg_in->header.stamp.sec, msg_in->header.stamp.nanosec);
    // Run the filter chain
    if (filter_chain_.update(*msg_in, msg_)) {
      //only publish result if filter succeeded
      output_pub_->publish(msg_);
      RCLCPP_INFO(nh_->get_logger(), "%d, %d", msg_.header.stamp.sec, msg_.header.stamp.nanosec);
    }
  }

[scan_to_scan_filter_chain-1] [INFO] [1691585756.502811379] [sick_tim_5xx.scan_to_scan_filter_chain]: 1691579413, 906227588 [scan_to_scan_filter_chain-1] [INFO] [1691585756.504288207] [sick_tim_5xx.scan_to_scan_filter_chain]: 1691579392, 906227588 [scan_to_scan_filter_chain-1] [INFO] [1691585757.162848118] [sick_tim_5xx.scan_to_scan_filter_chain]: 1691579413, 972615242 [scan_to_scan_filter_chain-1] [INFO] [1691585757.164226961] [sick_tim_5xx.scan_to_scan_filter_chain]: 1691579392, 972615242 [scan_to_scan_filter_chain-1] [INFO] [1691585757.827929301] [sick_tim_5xx.scan_to_scan_filter_chain]: 1691579414, 39208173 [scan_to_scan_filter_chain-1] [INFO] [1691585757.829719778] [sick_tim_5xx.scan_to_scan_filter_chain]: 1691579392, 39208173 [scan_to_scan_filter_chain-1] [INFO] [1691585758.502889853] [sick_tim_5xx.scan_to_scan_filter_chain]: 1691579414, 105945587 [scan_to_scan_filter_chain-1] [INFO] [1691585758.504508106] [sick_tim_5xx.scan_to_scan_filter_chain]: 1691579392, 105945587 [scan_to_scan_filter_chain-1] [INFO] [1691585759.167960141] [sick_tim_5xx.scan_to_scan_filter_chain]: 1691579414, 172862529 [scan_to_scan_filter_chain-1] [INFO] [1691585759.169524268] [sick_tim_5xx.scan_to_scan_filter_chain]: 1691579392, 172862529 [scan_to_scan_filter_chain-1] [INFO] [1691585759.832868401] [sick_tim_5xx.scan_to_scan_filter_chain]: 1691579414, 239361286 [scan_to_scan_filter_chain-1] [INFO] [1691585759.834581287] [sick_tim_5xx.scan_to_scan_filter_chain]: 1691579392, 239361286

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions