Go to the documentation of this file.00001 #include <boost/bind.hpp>
00002 #include <ros/ros.h>
00003 #include <turtlesim/Pose.h>
00004 #include <turtlesim/Velocity.h>
00005 #include <turtlesim/Spawn.h>
00006 #include <std_srvs/Empty.h>
00007
00008 turtlesim::PoseConstPtr g_pose;
00009 turtlesim::Pose g_goal;
00010
00011 enum State
00012 {
00013 FORWARD,
00014 STOP_FORWARD,
00015 TURN,
00016 STOP_TURN,
00017 };
00018
00019 State g_state = FORWARD;
00020 State g_last_state = FORWARD;
00021 bool g_first_goal_set = false;
00022
00023 #define PI 3.141592
00024
00025 void poseCallback(const turtlesim::PoseConstPtr& pose)
00026 {
00027 g_pose = pose;
00028 }
00029
00030 bool hasReachedGoal()
00031 {
00032 return fabsf(g_pose->x - g_goal.x) < 0.1 && fabsf(g_pose->y - g_goal.y) < 0.1 && fabsf(g_pose->theta - g_goal.theta) < 0.01;
00033 }
00034
00035 bool hasStopped()
00036 {
00037 return g_pose->angular_velocity < 0.0001 && g_pose->linear_velocity < 0.0001;
00038 }
00039
00040 void printGoal()
00041 {
00042 ROS_INFO("New goal [%f %f, %f]", g_goal.x, g_goal.y, g_goal.theta);
00043 }
00044
00045 void commandTurtle(ros::Publisher vel_pub, float linear, float angular)
00046 {
00047 turtlesim::Velocity vel;
00048 vel.linear = linear;
00049 vel.angular = angular;
00050 vel_pub.publish(vel);
00051 }
00052
00053 void stopForward(ros::Publisher vel_pub)
00054 {
00055 if (hasStopped())
00056 {
00057 ROS_INFO("Reached goal");
00058 g_state = TURN;
00059 g_goal.x = g_pose->x;
00060 g_goal.y = g_pose->y;
00061 g_goal.theta = fmod(g_pose->theta + PI/2.0, 2*PI);
00062 printGoal();
00063 }
00064 else
00065 {
00066 commandTurtle(vel_pub, 0, 0);
00067 }
00068 }
00069
00070 void stopTurn(ros::Publisher vel_pub)
00071 {
00072 if (hasStopped())
00073 {
00074 ROS_INFO("Reached goal");
00075 g_state = FORWARD;
00076 g_goal.x = cos(g_pose->theta) * 2 + g_pose->x;
00077 g_goal.y = sin(g_pose->theta) * 2 + g_pose->y;
00078 g_goal.theta = g_pose->theta;
00079 printGoal();
00080 }
00081 else
00082 {
00083 commandTurtle(vel_pub, 0, 0);
00084 }
00085 }
00086
00087
00088 void forward(ros::Publisher vel_pub)
00089 {
00090 if (hasReachedGoal())
00091 {
00092 g_state = STOP_FORWARD;
00093 commandTurtle(vel_pub, 0, 0);
00094 }
00095 else
00096 {
00097 commandTurtle(vel_pub, 1.0, 0.0);
00098 }
00099 }
00100
00101 void turn(ros::Publisher vel_pub)
00102 {
00103 if (hasReachedGoal())
00104 {
00105 g_state = STOP_TURN;
00106 commandTurtle(vel_pub, 0, 0);
00107 }
00108 else
00109 {
00110 commandTurtle(vel_pub, 0.0, 0.4);
00111 }
00112 }
00113
00114 void timerCallback(const ros::TimerEvent&, ros::Publisher vel_pub)
00115 {
00116 if (!g_pose)
00117 {
00118 return;
00119 }
00120
00121 if (!g_first_goal_set)
00122 {
00123 g_first_goal_set = true;
00124 g_state = FORWARD;
00125 g_goal.x = cos(g_pose->theta) * 2 + g_pose->x;
00126 g_goal.y = sin(g_pose->theta) * 2 + g_pose->y;
00127 g_goal.theta = g_pose->theta;
00128 printGoal();
00129 }
00130
00131 if (g_state == FORWARD)
00132 {
00133 forward(vel_pub);
00134 }
00135 else if (g_state == STOP_FORWARD)
00136 {
00137 stopForward(vel_pub);
00138 }
00139 else if (g_state == TURN)
00140 {
00141 turn(vel_pub);
00142 }
00143 else if (g_state == STOP_TURN)
00144 {
00145 stopTurn(vel_pub);
00146 }
00147 }
00148
00149 int main(int argc, char** argv)
00150 {
00151 ros::init(argc, argv, "turtle_stroll");
00152 ros::NodeHandle nh;
00153 ros::Subscriber pose_sub = nh.subscribe("pose", 1, poseCallback);
00154 ros::Publisher vel_pub = nh.advertise<turtlesim::Velocity>("command_velocity", 1);
00155
00156
00157
00158
00159
00160
00161
00162
00163
00164
00165
00166
00167
00168 ros::Timer timer = nh.createTimer(ros::Duration(0.016), boost::bind(timerCallback, _1, vel_pub));
00169
00170 ros::spin();
00171 }