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

Integrate differential drive motion model #33

Merged
merged 3 commits into from
Dec 30, 2022
Merged
Changes from 1 commit
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
Prev Previous commit
Add transform_tolerance parameter
nahueespinosa committed Dec 30, 2022
commit ca727525f3c53c6337a23c1e2722ae0a63e2dd3b
15 changes: 14 additions & 1 deletion beluga_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
@@ -159,6 +159,18 @@ AmclNode::AmclNode(const rclcpp::NodeOptions & options)
declare_parameter("resample_interval", rclcpp::ParameterValue(1), descriptor);
}

{
auto descriptor = rcl_interfaces::msg::ParameterDescriptor();
descriptor.description =
"Time with which to post-date the transform that is published, "
"to indicate that this transform is valid into the future";
descriptor.floating_point_range.resize(1);
descriptor.floating_point_range[0].from_value = 0;
descriptor.floating_point_range[0].to_value = std::numeric_limits<double>::max();
descriptor.floating_point_range[0].step = 0;
declare_parameter("transform_tolerance", rclcpp::ParameterValue(1.0), descriptor);
}

{
auto descriptor = rcl_interfaces::msg::ParameterDescriptor();
descriptor.description =
@@ -490,7 +502,8 @@ void AmclNode::timer_callback()
// TODO(nahuel): Publish estimated map to odom transform.
auto message = geometry_msgs::msg::TransformStamped{};
// Sending a transform that is valid into the future so that odom can be used.
message.header.stamp = now() + tf2::durationFromSec(1.0);
message.header.stamp = now() +
tf2::durationFromSec(get_parameter("transform_tolerance").as_double());
message.header.frame_id = get_parameter("global_frame_id").as_string();
message.child_frame_id = get_parameter("odom_frame_id").as_string();
message.transform.rotation.x = 0;
1 change: 1 addition & 0 deletions beluga_example/config/params.yaml
Original file line number Diff line number Diff line change
@@ -24,3 +24,4 @@ amcl:
z_hit: 0.5
z_rand: 0.5
sigma_hit: 0.2
transform_tolerance: 1.0