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

Feature param transform tolerance #50

Merged
merged 2 commits into from
Nov 14, 2023
Merged
Show file tree
Hide file tree
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
1 change: 1 addition & 0 deletions config/emcl2.param.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
/**:
ros__parameters:
odom_freq: 20
transform_tolerance: 0.2
global_frame_id: "map"
odom_frame_id: "odom"
base_frame_id: "base_link"
Expand Down
1 change: 1 addition & 0 deletions config/emcl2_quick_start.param.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
/**:
ros__parameters:
odom_freq: 20
transform_tolerance: 0.2
global_frame_id: "map"
odom_frame_id: "odom"
base_frame_id: "base_link"
Expand Down
1 change: 1 addition & 0 deletions include/emcl2/emcl2_node.h
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,7 @@ class EMcl2Node : public rclcpp::Node
bool scan_receive_;
bool map_receive_;
double init_x_, init_y_, init_t_;
double transform_tolerance_;

void publishPose(
double x, double y, double t, double x_dev, double y_dev, double t_dev, double xy_cov,
Expand Down
7 changes: 5 additions & 2 deletions src/emcl2_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,9 @@ void EMcl2Node::initCommunication(void)

this->declare_parameter("odom_freq", 20);
this->get_parameter("odom_freq", odom_freq_);

this->declare_parameter("transform_tolerance", 0.2);
this->get_parameter("transform_tolerance", transform_tolerance_);
}

void EMcl2Node::initTF(void)
Expand Down Expand Up @@ -310,11 +313,11 @@ void EMcl2Node::publishOdomFrame(double x, double y, double t)
}
tf2::convert(odom_to_map.pose, latest_tf_);
auto stamp = tf2_ros::fromMsg(scan_time_stamp_);
tf2::TimePoint transform_tolerance_ = stamp + tf2::durationFromSec(0.2);
tf2::TimePoint transform_expiration = stamp + tf2::durationFromSec(transform_tolerance_);

geometry_msgs::msg::TransformStamped tmp_tf_stamped;
tmp_tf_stamped.header.frame_id = global_frame_id_;
tmp_tf_stamped.header.stamp = tf2_ros::toMsg(transform_tolerance_);
tmp_tf_stamped.header.stamp = tf2_ros::toMsg(transform_expiration);
tmp_tf_stamped.child_frame_id = odom_frame_id_;
tf2::convert(latest_tf_.inverse(), tmp_tf_stamped.transform);

Expand Down
Loading