|
@@ -53,7 +53,7 @@ void Drive_Square::go_forward(const float square_side_length)
|
|
|
{
|
|
|
ROS_INFO("Go forward, dist:%f", dist);
|
|
|
publish_twist_cmd(linear_speed, 0);
|
|
|
- ros::Duration(0.10).sleep(); //100 ms
|
|
|
+ ros::Duration(0.05).sleep(); //50 ms
|
|
|
|
|
|
tf_Listener.lookupTransform(odom_frame, base_frame, ros::Time(0), tf_Transform);
|
|
|
float x = tf_Transform.getOrigin().x();
|
|
@@ -107,15 +107,18 @@ void Drive_Square::go_circle()
|
|
|
}
|
|
|
publish_twist_cmd(0, 0); //原地转弯完成后,需要立刻停止小车的旋转
|
|
|
ROS_INFO("Turning finish !!!");
|
|
|
- ros::Duration(0.1).sleep(); //100 ms
|
|
|
+ ros::Duration(1).sleep();
|
|
|
}
|
|
|
|
|
|
void Drive_Square::go()
|
|
|
{
|
|
|
- for (size_t i = 0; i < 4; i++)
|
|
|
+ while(ros::ok())
|
|
|
{
|
|
|
- Drive_Square::go_forward(square_side_length);
|
|
|
- Drive_Square::go_circle();
|
|
|
+ for (size_t i = 0; i < 4; i++)
|
|
|
+ {
|
|
|
+ Drive_Square::go_forward(square_side_length);
|
|
|
+ Drive_Square::go_circle();
|
|
|
+ }
|
|
|
}
|
|
|
}
|
|
|
|