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

Add frequency as parameter #21

Merged
merged 1 commit into from
Mar 23, 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
Original file line number Diff line number Diff line change
Expand Up @@ -105,12 +105,14 @@ class CollisionMonitor : public nav2_util::LifecycleNode
* @brief Supporting routine obtaining all ROS-parameters
* @param cmd_vel_in_topic Output name of cmd_vel_in topic
* @param cmd_vel_out_topic Output name of cmd_vel_out topic
* @param frequency Frequency of the loop running process_without_vel
* is required.
* @return True if all parameters were obtained or false in failure case
*/
bool getParameters(
std::string & cmd_vel_in_topic,
std::string & cmd_vel_out_topic);
std::string & cmd_vel_out_topic,
double & frequency);
/**
* @brief Supporting routine creating and configuring all polygons
* @param base_frame_id Robot base frame ID
Expand Down
12 changes: 9 additions & 3 deletions nav2_collision_monitor/src/collision_monitor_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,9 +57,10 @@ CollisionMonitor::on_configure(const rclcpp_lifecycle::State & /*state*/)

std::string cmd_vel_in_topic;
std::string cmd_vel_out_topic;
double frequency;

// Obtaining ROS parameters
if (!getParameters(cmd_vel_in_topic, cmd_vel_out_topic)) {
if (!getParameters(cmd_vel_in_topic, cmd_vel_out_topic, frequency)) {
return nav2_util::CallbackReturn::FAILURE;
}

Expand All @@ -72,7 +73,7 @@ CollisionMonitor::on_configure(const rclcpp_lifecycle::State & /*state*/)
for (std::shared_ptr<Polygon> polygon : polygons_) {
if (polygon->getActionType() == PUBLISH) {
timer_ = this->create_wall_timer(
100ms,
std::chrono::duration<double>{1.0 / frequency},
std::bind(&CollisionMonitor::process_without_vel, this));
break;
}
Expand Down Expand Up @@ -187,7 +188,8 @@ void CollisionMonitor::publishVelocity(const Action & robot_action)

bool CollisionMonitor::getParameters(
std::string & cmd_vel_in_topic,
std::string & cmd_vel_out_topic)
std::string & cmd_vel_out_topic,
double & frequency)
{
std::string base_frame_id, odom_frame_id;
tf2::Duration transform_tolerance;
Expand All @@ -202,6 +204,10 @@ bool CollisionMonitor::getParameters(
node, "cmd_vel_out_topic", rclcpp::ParameterValue("cmd_vel"));
cmd_vel_out_topic = get_parameter("cmd_vel_out_topic").as_string();

nav2_util::declare_parameter_if_not_declared(
node, "frequency", rclcpp::ParameterValue(10.0));
frequency = get_parameter("frequency").as_double();

nav2_util::declare_parameter_if_not_declared(
node, "base_frame_id", rclcpp::ParameterValue("base_footprint"));
base_frame_id = get_parameter("base_frame_id").as_string();
Expand Down