segbot_logical_navigator.cpp
Go to the documentation of this file.
00001 
00038 #include <actionlib/client/simple_action_client.h>
00039 #include <actionlib/client/terminal_state.h>
00040 #include <actionlib/server/simple_action_server.h>
00041 #include <boost/date_time/posix_time/posix_time.hpp>
00042 #include <boost/filesystem.hpp>
00043 #include <boost/foreach.hpp>
00044 #include <boost/thread/thread.hpp>
00045 #include <bwi_tools/resource_resolver.h>
00046 #include <message_filters/subscriber.h>
00047 #include <move_base_msgs/MoveBaseAction.h>
00048 #include <multi_level_map_msgs/ChangeCurrentLevel.h>
00049 #include <multi_level_map_msgs/LevelMetaData.h>
00050 #include <multi_level_map_msgs/MultiLevelMapData.h>
00051 #include <multi_level_map_utils/utils.h>
00052 #include <map_msgs/OccupancyGridUpdate.h>
00053 #include <nav_msgs/Odometry.h>
00054 #include <ros/ros.h>
00055 #include <tf/message_filter.h>
00056 #include <tf/transform_datatypes.h>
00057 #include <tf/transform_listener.h>
00058 
00059 #include <bwi_msgs/ResolveChangeFloor.h>
00060 #include <bwi_msgs/LogicalNavigationAction.h>
00061 #include <segbot_logical_translator/segbot_logical_translator.h>
00062 
00063 using bwi_planning_common::PlannerAtom;
00064 using bwi_planning_common::NO_DOOR_IDX;
00065 
00066 class SegbotLogicalNavigator : public segbot_logical_translator::SegbotLogicalTranslator {
00067 
00068   public:
00069 
00070     typedef actionlib::SimpleActionServer<bwi_msgs::LogicalNavigationAction> LogicalNavActionServer;
00071 
00072     SegbotLogicalNavigator();
00073 
00074     void execute(const bwi_msgs::LogicalNavigationGoalConstPtr &goal);
00075     bool changeFloorResolutionHandler(bwi_msgs::ResolveChangeFloor::Request &req,
00076                                       bwi_msgs::ResolveChangeFloor::Response &res);
00077 
00078 
00079   protected:
00080 
00081     void senseState(std::vector<PlannerAtom>& observations,
00082         size_t door_idx = NO_DOOR_IDX);
00083     bool approachDoor(const std::string& door_name,
00084         std::vector<PlannerAtom>& observations,
00085         std::string& error_message, bool gothrough = false);
00086     bool senseDoor(const std::string& door_name,
00087         std::vector<PlannerAtom>& observations,
00088         std::string& error_message);
00089 
00090     bool approachObject(const std::string& object_name,
00091         std::vector<PlannerAtom>& observations,
00092         std::string& error_message);
00093 
00094     bool resolveChangeFloorRequest(const std::string& new_room,
00095                                    const std::string& facing_door,
00096                                    std::string& floor_name,
00097                                    geometry_msgs::PoseWithCovarianceStamped& pose,
00098                                    std::string& error_message);
00099 
00100     bool changeFloor(const std::string& new_room,
00101                      const std::string& facing_door,
00102                      std::vector<PlannerAtom>& observations,
00103                      std::string& error_message);
00104 
00105     bool executeNavigationGoal(const geometry_msgs::PoseStamped& pose);
00106     void odometryHandler(const nav_msgs::Odometry::ConstPtr& odom);
00107 
00108     void currentLevelHandler(const multi_level_map_msgs::LevelMetaData::ConstPtr& current_level);
00109     void multimapHandler(const multi_level_map_msgs::MultiLevelMapData::ConstPtr& multimap);
00110 
00111     void publishNavigationMap(bool publish_map_with_doors = false,
00112                               bool wait_for_costmap_change = false);
00113 
00114     float robot_x_;
00115     float robot_y_;
00116     float robot_yaw_;
00117     std::string current_level_id_;
00118 
00119     double door_proximity_distance_;
00120 
00121     boost::shared_ptr<LogicalNavActionServer> execute_action_server_;
00122     bool execute_action_server_started_;
00123 
00124     ros::ServiceServer change_floor_resolution_server_;
00125     boost::shared_ptr<actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> > robot_controller_;
00126 
00127     boost::shared_ptr<tf::TransformListener> tf_;
00128     boost::shared_ptr<tf::MessageFilter<nav_msgs::Odometry> > tf_filter_;
00129     boost::shared_ptr<message_filters::Subscriber<nav_msgs::Odometry> > odom_subscriber_;
00130 
00131     ros::Subscriber current_level_subscriber_;
00132     ros::Subscriber multimap_subscriber_;
00133     ros::ServiceClient change_level_client_;
00134     bool change_level_client_available_;
00135     std::vector<multi_level_map_msgs::LevelMetaData> all_levels_;
00136     std::map<std::string, std::vector<bwi_planning_common::Door> > level_to_doors_map_;
00137     std::map<std::string, std::vector<std::string> > level_to_loc_names_map_;
00138     std::map<std::string, std::vector<int32_t> > level_to_loc_map_;
00139 
00140     ros::Publisher navigation_map_publisher_;
00141     bool last_map_published_with_doors_;
00142 
00143     // Subscribe to costmap and costmap updates message to ensure that a published navigation map has been accepted.
00144     void costmapSubscriber(const nav_msgs::OccupancyGrid::ConstPtr& costmap);
00145     void costmapUpdatesSubscriber(const map_msgs::OccupancyGridUpdate::ConstPtr& costmap_updates);
00146     ros::Subscriber costmap_subscriber_;
00147     ros::Subscriber costmap_updates_subscriber_;
00148     bool full_global_costmap_update_;
00149     int global_costmap_width_;
00150 
00151     bool robot_controller_available_;
00152 
00153 };
00154 
00155 SegbotLogicalNavigator::SegbotLogicalNavigator() :
00156     robot_x_(0), robot_y_(0), robot_yaw_(0), current_level_id_(""), execute_action_server_started_(false),
00157     change_level_client_available_(false), robot_controller_available_(false) {
00158 
00159   ROS_INFO("SegbotLogicalNavigator: Advertising services!");
00160 
00161   ros::param::param("~door_proximity_distance", door_proximity_distance_, 2.0);
00162 
00163   // Make sure you publish the default map at least once so that navigation can start up! Ensure this pub is latched.
00164   ros::NodeHandle private_nh("~");
00165   navigation_map_publisher_ = private_nh.advertise<nav_msgs::OccupancyGrid>("map", 1, true);
00166 
00167   robot_controller_.reset(
00168       new actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction>(
00169         "move_base", true));
00170 
00171   tf_.reset(new tf::TransformListener);
00172   odom_subscriber_.reset(new message_filters::Subscriber<nav_msgs::Odometry>);
00173   odom_subscriber_->subscribe(*nh_, "odom", 5);
00174   tf_filter_.reset(new tf::MessageFilter<nav_msgs::Odometry>(
00175         *odom_subscriber_, *tf_, global_frame_id_, 5));
00176   tf_filter_->registerCallback(
00177       boost::bind(&SegbotLogicalNavigator::odometryHandler, this, _1));
00178 
00179   execute_action_server_.reset(new LogicalNavActionServer(*nh_,
00180                                                           "execute_logical_goal",
00181                                                           boost::bind(&SegbotLogicalNavigator::execute, this, _1),
00182                                                           false));
00183 
00184   change_floor_resolution_server_ = nh_->advertiseService("resolve_change_floor",
00185                                                           &SegbotLogicalNavigator::changeFloorResolutionHandler,
00186                                                           this);
00187 
00188   current_level_subscriber_ = nh_->subscribe("level_mux/current_level",
00189                                              1,
00190                                              &SegbotLogicalNavigator::currentLevelHandler,
00191                                              this);
00192 
00193   multimap_subscriber_ = nh_->subscribe("map_metadata",
00194                                         1,
00195                                         &SegbotLogicalNavigator::multimapHandler,
00196                                         this);
00197 
00198   // Subscribe to the global costmap and Use the local costmap width as a substitute for max raytrace range.
00199   costmap_subscriber_ = nh_->subscribe("move_base/global_costmap/costmap",
00200                                        1,
00201                                        &SegbotLogicalNavigator::costmapSubscriber,
00202                                        this);
00203   costmap_updates_subscriber_ = nh_->subscribe("move_base/global_costmap/costmap_updates",
00204                                                1,
00205                                                &SegbotLogicalNavigator::costmapUpdatesSubscriber,
00206                                                this);
00207   global_costmap_width_ = -1;
00208   full_global_costmap_update_ = false;
00209 }
00210 
00211 void SegbotLogicalNavigator::currentLevelHandler(const multi_level_map_msgs::LevelMetaData::ConstPtr& current_level) {
00212   if (current_level_id_ != current_level->level_id) {
00213     std::string resolved_map_file = bwi_tools::resolveRosResource(current_level->map_file);
00214     ros::param::set("~map_file", resolved_map_file);
00215     std::string resolved_data_directory = bwi_tools::resolveRosResource(current_level->data_directory);
00216     ros::param::set("~data_directory", resolved_data_directory);
00217     if (SegbotLogicalTranslator::initialize()) {
00218       publishNavigationMap();
00219       // Once the translator is initialized, update the current level id.
00220       current_level_id_ = current_level->level_id;
00221     }
00222   }
00223 }
00224 
00225 void SegbotLogicalNavigator::costmapSubscriber(const nav_msgs::OccupancyGrid::ConstPtr& costmap) {
00226   global_costmap_width_ = costmap->info.width;
00227 }
00228 
00229 void SegbotLogicalNavigator::costmapUpdatesSubscriber(const map_msgs::OccupancyGridUpdate::ConstPtr& costmap_updates) {
00230   if (global_costmap_width_ != -1 && costmap_updates->width == global_costmap_width_) {
00231     full_global_costmap_update_ = true;
00232   }
00233 }
00234 
00235 void SegbotLogicalNavigator::multimapHandler(const multi_level_map_msgs::MultiLevelMapData::ConstPtr& multimap) {
00236 
00237   // Read in the objects for each level.
00238   BOOST_FOREACH(const multi_level_map_msgs::LevelMetaData &level, multimap->levels) {
00239     std::string resolved_data_directory = bwi_tools::resolveRosResource(level.data_directory);
00240     std::string doors_file = resolved_data_directory + "/doors.yaml";
00241     std::string locations_file = resolved_data_directory + "/locations.yaml";
00242     bwi_planning_common::readDoorFile(doors_file, level_to_doors_map_[level.level_id]);
00243     bwi_planning_common::readLocationFile(locations_file,
00244                                           level_to_loc_names_map_[level.level_id],
00245                                           level_to_loc_map_[level.level_id]);
00246   }
00247 
00248   // Start the change level service client.
00249   if (!change_level_client_available_) {
00250                 ROS_WARN("SegbotLogicalTranslator::multimapHandler: level_mux/change_current_level service is not yet available");
00251     change_level_client_available_ = ros::service::waitForService("level_mux/change_current_level", ros::Duration(5.0));
00252     if (change_level_client_available_) {
00253       change_level_client_ = nh_->serviceClient<multi_level_map_msgs::ChangeCurrentLevel>("level_mux/change_current_level");
00254     }
00255   }
00256 
00257 }
00258 
00259 void SegbotLogicalNavigator::publishNavigationMap(bool publish_map_with_doors, bool wait_for_costmap_change) {
00260   if (wait_for_costmap_change) {
00261     full_global_costmap_update_ = false;
00262   }
00263   if (publish_map_with_doors) {
00264     navigation_map_publisher_.publish(map_with_doors_);
00265     last_map_published_with_doors_ = true;
00266   } else {
00267     navigation_map_publisher_.publish(map_);
00268     last_map_published_with_doors_ = false;
00269   }
00270   if (wait_for_costmap_change) {
00271     int counter = 0;
00272     while (!full_global_costmap_update_ && counter < 100) {
00273       boost::this_thread::sleep(boost::posix_time::milliseconds(20));
00274       counter++;
00275     }
00276     if (counter == 100) {
00277       ROS_WARN_STREAM("segbot_logical_navigator: Waited 2 seconds for move_base global costmap to change, but it did not. I'll move forward with the assumption that the map changed and I missed the notification.");
00278     }
00279   }
00280 }
00281 
00282 void SegbotLogicalNavigator::senseState(std::vector<PlannerAtom>& observations, size_t door_idx) {
00283 
00284   PlannerAtom at;
00285   at.name = "at";
00286   size_t location_idx = getLocationIdx(bwi::Point2f(robot_x_, robot_y_));
00287   at.value.push_back(getLocationString(location_idx));
00288   observations.push_back(at);
00289 
00290   size_t num_doors = getNumDoors();
00291   bwi::Point2f robot_loc(robot_x_, robot_y_);
00292   bool beside_found = false;
00293   size_t beside_idx = NO_DOOR_IDX;
00294   size_t facing_idx = NO_DOOR_IDX;
00295 
00296   for (size_t door = 0; door < num_doors; ++door) {
00297 
00298     if (door_idx != NO_DOOR_IDX && door != door_idx) {
00299       // We've only requested information about a specific door (door_idx)
00300       continue;
00301     }
00302 
00303     if ((doors_[door].approach_names[0] != getLocationString(location_idx)) &&
00304         (doors_[door].approach_names[1] != getLocationString(location_idx))) {
00305       // We can't sense the current door since we're not in a location that this door connects.
00306       continue;
00307     }
00308 
00309     bool facing_door =
00310       isRobotFacingDoor(robot_loc, robot_yaw_, door_proximity_distance_, door);
00311     bool beside_door = !beside_found &&
00312       isRobotBesideDoor(robot_loc, robot_yaw_, door_proximity_distance_, door);
00313 
00314     if (facing_door) {
00315       facing_idx = door;
00316       beside_idx = door;
00317       break;
00318     }
00319 
00320     if (beside_door) {
00321       beside_idx = door;
00322       beside_found = true;
00323     }
00324   }
00325 
00326   for (size_t door = 0; door < num_doors; ++door) {
00327 
00328 
00329     PlannerAtom beside_door;
00330     beside_door.value.push_back(getDoorString(door));
00331     beside_door.name = "beside";
00332     if (beside_idx != door) {
00333       beside_door.name = "-" + beside_door.name;
00334     }
00335     observations.push_back(beside_door);
00336 
00337     PlannerAtom facing_door;
00338     facing_door.value.push_back(getDoorString(door));
00339     facing_door.name = "facing";
00340     if (facing_idx != door) {
00341       facing_door.name = "-" + facing_door.name;
00342     }
00343     observations.push_back(facing_door);
00344   }
00345 
00346   // If we are facing a door, also sense whether it is open
00347   if (facing_idx != NO_DOOR_IDX) {
00348     PlannerAtom door_open;
00349     door_open.value.push_back(getDoorString(facing_idx));
00350     if (isDoorOpen(facing_idx)) {
00351       door_open.name = "open";
00352       observations.push_back(door_open);
00353     } else {
00354       door_open.name = "-open";
00355       observations.push_back(door_open);
00356     }
00357   }
00358 }
00359 
00360 bool SegbotLogicalNavigator::executeNavigationGoal(
00361     const geometry_msgs::PoseStamped& pose) {
00362 
00363   if (!robot_controller_available_) {
00364     ROS_INFO("SegbotLogicalNavigator: Need to send command to robot. Waiting for move_base server...");
00365     robot_controller_->waitForServer();
00366     ROS_INFO("SegbotLogicalNavigator:   move_base server found!");
00367   }
00368 
00369   move_base_msgs::MoveBaseGoal goal;
00370   goal.target_pose = pose;
00371   robot_controller_->sendGoal(goal);
00372   bool navigation_request_complete = false;
00373   while (!navigation_request_complete) {
00374     if (execute_action_server_->isPreemptRequested() || !ros::ok()) {
00375       ROS_INFO("SegbotLogicalNavigator: Got pre-empted. Cancelling low level navigation task...");
00376       robot_controller_->cancelGoal();
00377       break;
00378     }
00379     navigation_request_complete = robot_controller_->waitForResult(ros::Duration(0.5));
00380   }
00381 
00382   if (navigation_request_complete) {
00383     actionlib::SimpleClientGoalState state = robot_controller_->getState();
00384     return state == actionlib::SimpleClientGoalState::SUCCEEDED;
00385   }
00386 
00387   // If we're here, then we preempted the request ourselves. Let's mark our current request as not successful.
00388   return false;
00389 }
00390 
00391 void SegbotLogicalNavigator::odometryHandler(
00392     const nav_msgs::Odometry::ConstPtr& odom) {
00393   geometry_msgs::PoseStamped pose_in, pose_out;
00394   pose_in.header = odom->header;
00395   pose_in.pose = odom->pose.pose;
00396   tf_->transformPose(global_frame_id_, pose_in, pose_out);
00397   robot_x_ = pose_out.pose.position.x;
00398   robot_y_ = pose_out.pose.position.y;
00399   //ROS_INFO("OdometryHandler X:%f Y:%f" , robot_x_, robot_y_);
00400 
00401   robot_yaw_ = tf::getYaw(pose_out.pose.orientation);
00402 
00403   if(!execute_action_server_started_) {
00404     execute_action_server_->start();
00405     execute_action_server_started_ = true;
00406   }
00407 }
00408 
00409 bool SegbotLogicalNavigator::approachDoor(const std::string& door_name,
00410     std::vector<PlannerAtom>& observations,
00411     std::string& error_message, bool gothrough) {
00412   error_message = "";
00413 
00414   size_t door_idx = getDoorIdx(door_name);
00415   if (door_idx == NO_DOOR_IDX) {
00416     // Interface failure
00417     error_message = "Could not resolve argument: " + door_name;
00418     return false;
00419   } else {
00420 
00421 
00422     bwi::Point2f approach_pt;
00423     float approach_yaw = 0;
00424     bool door_approachable = false;
00425 
00426     if (!gothrough) {
00427       publishNavigationMap(true, true);
00428       door_approachable = getApproachPoint(door_idx, bwi::Point2f(robot_x_, robot_y_), approach_pt, approach_yaw);
00429     } else {
00430       publishNavigationMap(false, true);
00431       door_approachable = getThroughDoorPoint(door_idx, bwi::Point2f(robot_x_, robot_y_), approach_pt, approach_yaw);
00432       enableStaticCostmap(false);
00433     }
00434 
00435     if (door_approachable) {
00436       geometry_msgs::PoseStamped pose;
00437       pose.header.stamp = ros::Time::now();
00438       pose.header.frame_id = global_frame_id_;
00439       pose.pose.position.x = approach_pt.x;
00440       pose.pose.position.y = approach_pt.y;
00441       // std::cout << "approaching " << approach_pt.x << "," << approach_pt.y << std::endl;
00442       tf::quaternionTFToMsg(
00443           tf::createQuaternionFromYaw(approach_yaw), pose.pose.orientation);
00444       bool success = executeNavigationGoal(pose);
00445 
00446       if (gothrough) {
00447         enableStaticCostmap(true);
00448       }
00449       // Publish the observable fluents. Since we're likely going to sense the door, make sure the no-doors map was
00450       // published.
00451       publishNavigationMap(false, true);
00452       senseState(observations, door_idx);
00453 
00454       return success;
00455     } else {
00456       // Planning failure
00457       if (gothrough) {
00458         enableStaticCostmap(true);
00459       }
00460       error_message = "Cannot interact with " + door_name + " from here.";
00461       return false;
00462     }
00463   }
00464 }
00465 
00466 bool SegbotLogicalNavigator::approachObject(const std::string& object_name,
00467     std::vector<PlannerAtom>& observations,
00468     std::string& error_message) {
00469 
00470   error_message = "";
00471   observations.clear();
00472 
00473   if (object_approach_map_.find(object_name) != object_approach_map_.end()) {
00474 
00475     if (!isObjectApproachable(object_name, bwi::Point2f(robot_x_, robot_y_))) {
00476       error_message = "Cannot interact with " + object_name + " from the robot's current location.";
00477       return false;
00478     }
00479 
00480     publishNavigationMap(true);
00481 
00482     geometry_msgs::PoseStamped pose;
00483     pose.header.stamp = ros::Time::now();
00484     pose.header.frame_id = global_frame_id_;
00485     pose.pose = object_approach_map_[object_name];
00486     bool success = executeNavigationGoal(pose);
00487 
00488     // Publish the observable fluents
00489     senseState(observations, NO_DOOR_IDX);
00490     PlannerAtom facing;
00491     facing.name = "facing";
00492     facing.value.push_back(object_name);
00493 
00494     PlannerAtom beside;
00495     beside.name = "beside";
00496     beside.value.push_back(object_name);
00497     if (!success) {
00498       facing.name = "-facing";
00499       beside.name = "-beside";
00500     }
00501     observations.push_back(facing);
00502     observations.push_back(beside);
00503     return success;
00504   }
00505 
00506   error_message = object_name + " does not exist.";
00507   return false;
00508 }
00509 
00510 bool SegbotLogicalNavigator::resolveChangeFloorRequest(const std::string& new_room,
00511                                                        const std::string& facing_door,
00512                                                        std::string& floor_name,
00513                                                        geometry_msgs::PoseWithCovarianceStamped& pose,
00514                                                        std::string& error_message) {
00515 
00516   // Make sure we can change floors and all arguments are correct.
00517   if (!change_level_client_available_) {
00518                 //Make an attempt to connect to see if the client has been made avaliable since instantiation before giving up
00519                 change_level_client_available_ = ros::service::waitForService("level_mux/change_current_level",ros::Duration(0.5));
00520                 if(change_level_client_available_){
00521                         change_level_client_ = nh_->serviceClient<multi_level_map_msgs::ChangeCurrentLevel>("level_mux/change_current_level");
00522                 }
00523                 else {
00524     error_message = "SegbotLogicalNavigator has not received the multimap. Cannot change floors!";
00525     return false;
00526                 }
00527   }
00528     bool new_room_found = false;
00529     typedef std::pair<std::string, std::vector<std::string> > Level2LocNamesPair;
00530     BOOST_FOREACH(const Level2LocNamesPair& level_to_loc, level_to_loc_names_map_) {
00531       if (std::find(level_to_loc.second.begin(), level_to_loc.second.end(), new_room) != level_to_loc.second.end()) {
00532         new_room_found = true;
00533         floor_name = level_to_loc.first;
00534         break;
00535       }
00536     }
00537 
00538     if (!new_room_found) {
00539       error_message = "Location " + new_room + " has not been defined on any floor!";
00540       return false;
00541     }
00542 
00543   if (current_level_id_ == floor_name) {
00544     error_message = "The robot is already on " + floor_name + " (in which " + new_room + " exists)!";
00545     return false;
00546   }
00547 
00548   // Now find the door on this floor that corresponds to facing_door
00549   bool door_found;
00550   bwi_planning_common::Door door;
00551   BOOST_FOREACH(const bwi_planning_common::Door& floor_door, level_to_doors_map_[floor_name]) {
00552     if (floor_door.name == facing_door) {
00553       door_found = true;
00554       door = floor_door;
00555       break;
00556     }
00557   }
00558 
00559   if (!door_found) {
00560     error_message = "Door " + facing_door + " has not been defined on floor " + floor_name + "!";
00561     return false;
00562   }
00563 
00564   bwi::Point2f approach_pt;
00565   float approach_yaw = 0;
00566   if (door.approach_names[0] == new_room) {
00567     approach_pt = door.approach_points[0];
00568     approach_yaw = door.approach_yaw[0];
00569   } else if (door.approach_names[1] == new_room) {
00570     approach_pt = door.approach_points[1];
00571     approach_yaw = door.approach_yaw[1];
00572   } else {
00573     error_message = "Door " + facing_door + " does not connect location " + new_room + "!";
00574     return false;
00575   }
00576 
00577   /* Setup return values */
00578   pose.header.stamp = ros::Time::now();
00579   pose.header.frame_id = global_frame_id_;
00580   pose.pose.pose.position.x = approach_pt.x;
00581   pose.pose.pose.position.y = approach_pt.y;
00582   tf::quaternionTFToMsg( tf::createQuaternionFromYaw(approach_yaw), pose.pose.pose.orientation);
00583   pose.pose.covariance[0] = 0.1;
00584   pose.pose.covariance[7] = 0.1f;
00585   pose.pose.covariance[35] = 0.25f;
00586 
00587   return true;
00588 }
00589 
00590 bool SegbotLogicalNavigator::changeFloor(const std::string& new_room,
00591                                          const std::string& facing_door,
00592                                          std::vector<PlannerAtom>& observations,
00593                                          std::string& error_message) {
00594         //Just making sure it gets called correctly
00595         ROS_INFO_STREAM("SegbotLogicalNavigator: changefloor called");
00596 
00597   error_message = "";
00598   observations.clear();
00599 
00600   multi_level_map_msgs::ChangeCurrentLevel srv;
00601   srv.request.publish_initial_pose = true;
00602 
00603   if (!(resolveChangeFloorRequest(new_room, 
00604                                   facing_door, 
00605                                   srv.request.new_level_id, 
00606                                   srv.request.initial_pose, 
00607                                   error_message))) {
00608                 ROS_ERROR_STREAM("SegbotLogicalTranslator::resolveChangeFloorRequest failed. Error message: " << error_message);
00609     return false;
00610   }
00611 
00612   if (change_level_client_.call(srv)) {
00613     if (!srv.response.success) {
00614       error_message = srv.response.error_message;
00615                         ROS_ERROR_STREAM("SegbotLogicalTranslator::changeFloor service call failed. Error message: " << error_message);
00616       return false;
00617     }
00618 
00619     // Yea! the call succeeded! Wait for current_level_id_ to be changed once everything gets updated.
00620     ros::Rate r(1);
00621     while (current_level_id_ != srv.request.new_level_id){
00622                         ROS_INFO_STREAM("SegbotLogicalTranslator::changeFloor: Waiting for changes to be updated...");
00623                         r.sleep();
00624                 }
00625     // Publish the observable fluents
00626     senseState(observations);
00627     return true;
00628   } else {
00629     error_message = "ChangeCurrentLevel service call failed for unknown reason.";
00630     return false;
00631   }
00632 }
00633 
00634 bool SegbotLogicalNavigator::senseDoor(const std::string& door_name,
00635     std::vector<PlannerAtom>& observations,
00636     std::string& error_message) {
00637   error_message = "";
00638   size_t door_idx =
00639     bwi_planning_common::resolveDoor(door_name, doors_);
00640   if (door_idx == bwi_planning_common::NO_DOOR_IDX) {
00641     error_message = "Door " + door_name + " does not exist!";
00642     return false;
00643   }
00644   bool door_open = isDoorOpen(door_idx);
00645   PlannerAtom open;
00646   open.name = "open";
00647   if (!door_open) {
00648     open.name = "-" + open.name;
00649   }
00650   open.value.push_back(door_name);
00651   observations.push_back(open);
00652   return true;
00653 }
00654 
00655 void SegbotLogicalNavigator::execute(const bwi_msgs::LogicalNavigationGoalConstPtr& goal) {
00656 
00657   bwi_msgs::LogicalNavigationResult res;
00658   res.observations.clear();
00659 
00660   if (goal->command.name == "approach") {
00661     res.success = approachDoor(goal->command.value[0], res.observations, res.status, false);
00662   } else if (goal->command.name == "gothrough") {
00663     res.success = approachDoor(goal->command.value[0], res.observations,
00664         res.status, true);
00665   } else if (goal->command.name == "sensedoor") {
00666     res.success = senseDoor(goal->command.value[0], res.observations,
00667         res.status);
00668   } else if (goal->command.name == "goto") {
00669     res.success = approachObject(goal->command.value[0], res.observations,
00670         res.status);
00671   } else if (goal->command.name == "changefloor") {
00672     res.success = changeFloor(goal->command.value[0], goal->command.value[1], res.observations, res.status);
00673   } else {
00674     res.success = true;
00675     res.status = "";
00676     senseState(res.observations);
00677   }
00678 
00679   if (res.success) {
00680     execute_action_server_->setSucceeded(res);
00681   } else if (execute_action_server_->isPreemptRequested()) {
00682     execute_action_server_->setPreempted(res);
00683   } else {
00684     execute_action_server_->setAborted(res);
00685   }
00686 
00687 }
00688 
00689 bool SegbotLogicalNavigator::changeFloorResolutionHandler(bwi_msgs::ResolveChangeFloor::Request  &req,
00690                                                           bwi_msgs::ResolveChangeFloor::Response &res) {
00691   res.success = resolveChangeFloorRequest(req.new_room, req.facing_door, res.floor_name, res.pose, res.error_message);
00692   return true;
00693 }
00694 
00695 int main(int argc, char *argv[]) {
00696 
00697   ros::init(argc, argv, "segbot_logical_translator");
00698   ros::NodeHandle nh;
00699 
00700   ROS_INFO("SegbotLogicalNavigator: Starting up node...");
00701   SegbotLogicalNavigator handler;
00702   ros::MultiThreadedSpinner spinner(2);
00703   spinner.spin();
00704   ROS_INFO("SegbotLogicalNavigator: Stopping node.");
00705 
00706   return 0;
00707 }


segbot_logical_translator
Author(s): Piyush Khandelwal
autogenerated on Thu Jun 6 2019 21:37:44