Skip to content
Open
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
4 changes: 3 additions & 1 deletion src/robot/control/src/control_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,9 @@ geometry_msgs::msg::Twist ControlCore::calculateControlCommand(
// Or just constant linear velocity as per prompt "make sure the robot follows the path"

// Just use the configured linear velocity
twist.linear.x = linear_velocity_;
double speed_factor =
1.0 - (std::abs(output) / max_steering_angle_ * 0.5); // during turns slows down to avoid overshoot
twist.linear.x = linear_velocity_ * speed_factor;
twist.angular.z = output;

return twist;
Expand Down
7 changes: 5 additions & 2 deletions src/robot/control/src/control_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,8 @@ void ControlNode::processParameters()
this->declare_parameter<std::string>("cmd_vel_topic", "/cmd_vel");
this->declare_parameter<int>("control_period_ms", 100);
this->declare_parameter<double>("kp", 1.0);
this->declare_parameter<double>("ki", 0.0);
this->declare_parameter<double>("kd", 0.0);
this->declare_parameter<double>("ki", 0.6);
this->declare_parameter<double>("kd", 0.4);
this->declare_parameter<double>("max_steering_angle", 1.5);
this->declare_parameter<double>("linear_velocity", 1.5);

Expand Down Expand Up @@ -87,6 +87,9 @@ void ControlNode::followPath()
{
if (control_.isPathEmpty()) {
RCLCPP_WARN_THROTTLE(this->get_logger(), *this->get_clock(), 3000, "Path is empty. Waiting for new path.");
// Publish stop command to halt the robot
geometry_msgs::msg::Twist stop_cmd;
cmd_vel_publisher_->publish(stop_cmd);
return;
}

Expand Down