Skip to content
Snippets Groups Projects
Commit 15afd12d authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Solved a bug: the steering angle changed with the sign tranlational velocity....

Solved a bug: the steering angle changed with the sign tranlational velocity. The radius is now computed without sign.
parent 7f033909
No related branches found
No related tags found
1 merge request!1Development
...@@ -125,8 +125,11 @@ void ModelCarControlAlgNode::cmd_vel_callback(const geometry_msgs::Twist::ConstP ...@@ -125,8 +125,11 @@ void ModelCarControlAlgNode::cmd_vel_callback(const geometry_msgs::Twist::ConstP
if(msg->angular.z==0.0) if(msg->angular.z==0.0)
radius=std::numeric_limits<double>::max(); radius=std::numeric_limits<double>::max();
else else
radius=msg->linear.x/msg->angular.z; radius=fabs(msg->linear.x/msg->angular.z);
this->steer_angle_control=atan2(this->config_.axel_distance,radius); if(msg->angular.z>0.0)
this->steer_angle_control=atan2(this->config_.axel_distance,radius);
else
this->steer_angle_control=atan2(this->config_.axel_distance,-radius);
if(this->steer_angle_control>1.5707) if(this->steer_angle_control>1.5707)
this->steer_angle_control-=3.14159; this->steer_angle_control-=3.14159;
if(this->steer_angle_control>this->config_.max_steer_angle) if(this->steer_angle_control>this->config_.max_steer_angle)
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment