Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <vector>
00038 #include <string>
00039
00040 #include <ros/ros.h>
00041 #include <tf/tf.h>
00042 #include <move_base_msgs/MoveBaseAction.h>
00043 #include <actionlib/client/simple_action_client.h>
00044 #include <geometry_msgs/Pose2D.h>
00045 #include <lse_sensor_msgs/Nostril.h>
00046 #include <roomba_500_series/Battery.h>
00047 #include <roomba_500_series/GoDockAction.h>
00048 #include <geometry_msgs/Twist.h>
00049
00050 typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;
00051
00052 bool nextGoal;
00053 bool needToBackUp;
00054
00055 roomba_500_series::Battery battery;
00056
00057 void goalDoneCallback(const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result)
00058 {
00059 ROS_INFO("Goal is done!");
00060 if(state.state_ == actionlib::SimpleClientGoalState::SUCCEEDED) nextGoal = true;
00061 else if(state.state_ == actionlib::SimpleClientGoalState::ABORTED) needToBackUp = true;
00062 }
00063
00064 void goalActiveCallback()
00065 {
00066
00067 }
00068
00069 void goalFeedbackCallback(const move_base_msgs::MoveBaseFeedbackConstPtr &feedback)
00070 {
00071
00072 }
00073
00074 void noseCallback(const lse_sensor_msgs::Nostril::ConstPtr& nose)
00075 {
00076
00077 }
00078
00079 void batteryCallback(const roomba_500_series::Battery::ConstPtr& batt)
00080 {
00081 battery.level = batt->level;
00082 battery.dock = batt->dock;
00083 }
00084
00085 int main(int argc, char** argv)
00086 {
00087 ros::init(argc, argv, "fctuc_open_day_demo");
00088
00089 ROS_INFO("Welcome to FCTUC Open Day Demo!");
00090
00091 ros::NodeHandle n;
00092
00093
00094
00095 ros::Subscriber nose_sub = n.subscribe("/nose", 20, noseCallback);
00096 ros::Subscriber batt_sub = n.subscribe("/battery", 20, batteryCallback);
00097
00098
00099
00100
00101
00102
00103 std::string tf_prefix;
00104 n.param<std::string>("tf_prefix", tf_prefix, "");
00105
00106 std::string file_path;
00107 n.param<std::string>("demo/file_name", file_path, "demo.goal");
00108
00109 FILE * goalsFile;
00110 goalsFile = fopen(file_path.c_str(), "r");
00111 if(goalsFile == NULL)
00112 {
00113 ROS_INFO("Cannot open file %s", file_path.c_str());
00114 ROS_BREAK();
00115 }
00116
00117 std::vector<geometry_msgs::Pose2D> targets;
00118 std::vector<geometry_msgs::Pose2D>::iterator target;
00119
00120
00121
00122
00123
00124
00125 geometry_msgs::Pose2D pose;
00126
00127 float z, qx, qy, qz, qw;
00128 while(!feof(goalsFile))
00129 {
00130 fscanf(goalsFile, "Frame:/map, Position(%f, %f, %f), Orientation(%f, %f, %f, %f) = Angle: %lf\n", &(pose.x), &(pose.y), &z, &qx, &qy, &qz, &qw, &(pose.theta));
00131 targets.push_back(pose);
00132 }
00133
00134
00135 MoveBaseClient ac("move_base", true);
00136
00137 ROS_INFO("Waiting for the move_base action server to come online... Forgot to launch move_base now did we?");
00138 while(!ac.waitForServer(ros::Duration(5.0))){;}
00139 ROS_INFO("Found the move_base action server! Moving on...");
00140
00141 battery.level = 100.0;
00142 battery.dock = false;
00143 needToBackUp = false;
00144 nextGoal = false;
00145 bool sendGoal = true;
00146 bool docking = false;
00147 int backUpCounter = 0;
00148 target = targets.begin();
00149 ROS_INFO("Lets have some fun...");
00150
00151 ros::Rate r(10);
00152 while(ros::ok())
00153 {
00154
00155
00156
00157
00158
00159
00160
00161
00162
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173
00174
00175
00176
00177
00178
00179
00180
00181
00182
00183
00184
00185
00186
00187
00188
00189
00190
00191
00192
00193
00194
00195
00196
00197
00198
00199 if(nextGoal)
00200 {
00201
00202 if(docking)
00203 {
00204 ROS_INFO("Lets see if I can bullseye the dock...");
00205
00206
00207
00208
00209
00210
00211
00212
00213
00214
00215
00216 docking = false;
00217 }
00218 else
00219 {
00220 target++;
00221 if(target==targets.end()) target=targets.begin();
00222 }
00223 sendGoal = true;
00224 nextGoal = false;
00225 }
00226
00227
00228 if(sendGoal || (battery.level<50.0 && !battery.dock && !docking))
00229 {
00230 std::string frame_name = tf_prefix;
00231 move_base_msgs::MoveBaseGoal goal;
00232
00233
00234 goal.target_pose.header.frame_id = frame_name.append("/map");
00235 goal.target_pose.header.stamp = ros::Time::now();
00236
00237
00238 if(battery.level<50.0 && !battery.dock)
00239 {
00240
00241
00242
00243
00244
00245 }
00246 else
00247 {
00248 ROS_INFO("Sending next goal... How long do we have to keep this up?");
00249 goal.target_pose.pose.position.x = target->x;
00250 goal.target_pose.pose.position.y = target->y;
00251 goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(target->theta);
00252 }
00253
00254 sendGoal = false;
00255 ac.sendGoal(goal, boost::bind(&goalDoneCallback, _1, _2), boost::bind(&goalActiveCallback), boost::bind(&goalFeedbackCallback, _1));
00256 }
00257
00258
00259
00260
00261 ros::spinOnce();
00262 r.sleep();
00263 }
00264
00265 ROS_INFO("Exiting FCTUC Open Day Demo...");
00266
00267 return 0;
00268 }