SMACC2
Loading...
Searching...
No Matches
Classes | Functions
cl_nav2z::forward_local_planner Namespace Reference

Classes

class  ForwardLocalPlanner
 

Functions

void clamp (rclcpp::Node::SharedPtr nh_, geometry_msgs::msg::Twist &cmd_vel, double max_linear_x_speed_, double max_angular_z_speed_)
 

Function Documentation

◆ clamp()

void cl_nav2z::forward_local_planner::clamp ( rclcpp::Node::SharedPtr  nh_,
geometry_msgs::msg::Twist &  cmd_vel,
double  max_linear_x_speed_,
double  max_angular_z_speed_ 
)

Definition at line 282 of file forward_local_planner.cpp.

285{
286 if (max_angular_z_speed_ == 0 || max_linear_x_speed_ == 0) return;
287
288 if (cmd_vel.angular.z == 0)
289 {
290 cmd_vel.linear.x = max_linear_x_speed_;
291 }
292 else
293 {
294 double kurvature = cmd_vel.linear.x / cmd_vel.angular.z;
295
296 double linearAuthority = fabs(cmd_vel.linear.x / max_linear_x_speed_);
297 double angularAuthority = fabs(cmd_vel.angular.z / max_angular_z_speed_);
298 if (linearAuthority < angularAuthority)
299 {
300 // lets go to maximum linear speed
301 cmd_vel.linear.x = max_linear_x_speed_;
302 cmd_vel.angular.z = kurvature / max_linear_x_speed_;
303 RCLCPP_WARN_STREAM(
304 nh_->get_logger(), "k=" << kurvature << "lets go to maximum linear capacity: " << cmd_vel);
305 }
306 else
307 {
308 // lets go with maximum angular speed
309 cmd_vel.angular.x = max_angular_z_speed_;
310 cmd_vel.linear.x = kurvature * max_angular_z_speed_;
311 RCLCPP_WARN_STREAM(nh_->get_logger(), "lets go to maximum angular capacity: " << cmd_vel);
312 }
313 }
314}