00001 #include <ros/ros.h>
00002 #include <turtlesim/Pose.h>
00003 #include <turtlesim/Velocity.h>
00004 #include <actionlib/server/simple_action_server.h>
00005 #include <turtle_actionlib/ShapeAction.h>
00006 #include <cmath>
00007 #include <math.h>
00008 #include <angles/angles.h>
00009
00010
00011 class ShapeAction
00012 {
00013 public:
00014
00015 ShapeAction(std::string name) :
00016 as_(nh_, name),
00017 action_name_(name)
00018 {
00019
00020 as_.registerGoalCallback(boost::bind(&ShapeAction::goalCB, this));
00021 as_.registerPreemptCallback(boost::bind(&ShapeAction::preemptCB, this));
00022
00023
00024 sub_ = nh_.subscribe("/turtle1/pose", 1, &ShapeAction::controlCB, this);
00025 pub_ = nh_.advertise<turtlesim::Velocity>("/turtle1/command_velocity", 1);
00026 }
00027
00028 ~ShapeAction(void)
00029 {
00030 }
00031
00032 void goalCB()
00033 {
00034
00035 turtle_actionlib::ShapeGoal goal = *as_.acceptNewGoal();
00036
00037 edges_ = goal.edges;
00038 radius_ = goal.radius;
00039
00040
00041 interior_angle_ = ((edges_-2)*M_PI)/edges_;
00042 apothem_ = radius_*cos(M_PI/edges_);
00043
00044 side_len_ = apothem_ * 2* tan( M_PI/edges_);
00045
00046 result_.apothem = apothem_;
00047 result_.interior_angle = interior_angle_;
00048 edge_progress_ =0;
00049 start_edge_ = true;
00050 }
00051
00052 void preemptCB()
00053 {
00054 ROS_INFO("%s: Preempted", action_name_.c_str());
00055
00056 as_.setPreempted();
00057 }
00058
00059 void controlCB(const turtlesim::Pose::ConstPtr& msg)
00060 {
00061
00062 if (!as_.isActive())
00063 return;
00064
00065
00066 double l_scale = 6.0;
00067 double a_scale = 6.0;
00068 double error_tol = 0.00001;
00069
00070 if (edge_progress_ < edges_)
00071 {
00072 if (start_edge_)
00073 {
00074 start_x_ = msg->x;
00075 start_y_ = msg->y;
00076 start_theta_ = msg->theta;
00077 start_edge_ = false;
00078 }
00079
00080
00081 dis_error_ = side_len_ - fabs(sqrt((start_x_- msg->x)*(start_x_-msg->x) + (start_y_-msg->y)*(start_y_-msg->y)));
00082 theta_error_ = angles::normalize_angle_positive(M_PI - interior_angle_ - (msg->theta - start_theta_));
00083
00084 if (dis_error_ > error_tol)
00085 {
00086 command_.linear = l_scale*dis_error_;
00087 command_.angular = 0;
00088 }
00089 else if (dis_error_ < error_tol && fabs(theta_error_)> error_tol)
00090 {
00091 command_.linear = 0;
00092 command_.angular = a_scale*theta_error_;
00093 }
00094 else if (dis_error_ < error_tol && fabs(theta_error_)< error_tol)
00095 {
00096 command_.linear = 0;
00097 command_.angular = 0;
00098 start_edge_ = true;
00099 edge_progress_++;
00100 }
00101 else
00102 {
00103 command_.linear = l_scale*dis_error_;
00104 command_.angular = a_scale*theta_error_;
00105 }
00106
00107 pub_.publish(command_);
00108
00109 }
00110 else
00111 {
00112 ROS_INFO("%s: Succeeded", action_name_.c_str());
00113
00114 as_.setSucceeded(result_);
00115 }
00116 }
00117
00118 protected:
00119
00120 ros::NodeHandle nh_;
00121 actionlib::SimpleActionServer<turtle_actionlib::ShapeAction> as_;
00122 std::string action_name_;
00123 double radius_, apothem_, interior_angle_, side_len_;
00124 double start_x_, start_y_, start_theta_;
00125 double dis_error_, theta_error_;
00126 int edges_ , edge_progress_;
00127 bool start_edge_;
00128 turtlesim::Velocity command_;
00129 turtle_actionlib::ShapeResult result_;
00130 ros::Subscriber sub_;
00131 ros::Publisher pub_;
00132 };
00133
00134 int main(int argc, char** argv)
00135 {
00136 ros::init(argc, argv, "turtle_shape");
00137
00138 ShapeAction shape(ros::this_node::getName());
00139 ros::spin();
00140
00141 return 0;
00142 }