object_controller_plugin.cc
Go to the documentation of this file.
00001 /*
00002     Copyright (c) 2010, Daniel Hewlett, Antons Rebguns
00003     All rights reserved.
00004 
00005     Redistribution and use in source and binary forms, with or without
00006     modification, are permitted provided that the following conditions are met:
00007         * Redistributions of source code must retain the above copyright
00008         notice, this list of conditions and the following disclaimer.
00009         * Redistributions in binary form must reproduce the above copyright
00010         notice, this list of conditions and the following disclaimer in the
00011         documentation and/or other materials provided with the distribution.
00012         * Neither the name of the <organization> nor the
00013         names of its contributors may be used to endorse or promote products
00014         derived from this software without specific prior written permission.
00015 
00016     THIS SOFTWARE IS PROVIDED BY Antons Rebguns <email> ''AS IS'' AND ANY
00017     EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018     WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019     DISCLAIMED. IN NO EVENT SHALL Antons Rebguns <email> BE LIABLE FOR ANY
00020     DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021     (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022     LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023     ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024     (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025     SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 
00029 #include <segbot_gazebo_plugins/object_controller_plugin.h>
00030 
00031 #include <math/gzmath.hh>
00032 #include <sdf/sdf.hh>
00033 
00034 #include <ros/ros.h>
00035 #include <tf/transform_broadcaster.h>
00036 #include <tf/transform_listener.h>
00037 #include <geometry_msgs/Twist.h>
00038 #include <nav_msgs/GetMap.h>
00039 #include <nav_msgs/Odometry.h>
00040 #include <boost/bind.hpp>
00041 #include <boost/thread/mutex.hpp>
00042 
00043 namespace gazebo {
00044 
00045   ObjectControllerPlugin::ObjectControllerPlugin() {}
00046 
00047   ObjectControllerPlugin::~ObjectControllerPlugin() {
00048     delete rosnode_;
00049     delete transform_broadcaster_;
00050   }
00051 
00052   // Load the controller
00053   void ObjectControllerPlugin::Load(physics::ModelPtr _parent, 
00054       sdf::ElementPtr _sdf) {
00055 
00056     this->parent = _parent;
00057     this->world = _parent->GetWorld();
00058 
00059     /* Parse parameters - all params are optional */
00060 
00061     this->modelNamespace = "";
00062     if (!_sdf->HasElement("robotNamespace")) {
00063       ROS_INFO("OCPlugin missing <robotNamespace>, defaults to \"%s\"", 
00064           this->modelNamespace.c_str());
00065     } else {
00066       this->modelNamespace = 
00067         _sdf->GetElement("robotNamespace")->GetValueString();
00068     }
00069 
00070     this->topicName = "cmd_vel";
00071     if (!_sdf->HasElement("topicName")) {
00072       ROS_WARN("OCPlugin (%s) missing <topicName>, defaults to \"%s\"", 
00073           this->modelNamespace.c_str(), this->topicName.c_str());
00074     } else {
00075       this->topicName = _sdf->GetElement("topicName")->GetValueString();
00076     }
00077 
00078     this->globalFrame = "/map";
00079     if (!_sdf->HasElement("globalFrame")) {
00080       ROS_WARN("OCPlugin (%s) missing globalFrame, defaults to \"%s\"",
00081           this->modelNamespace.c_str(), this->globalFrame.c_str());
00082     } else {
00083       this->globalFrame = _sdf->GetElement("globalFrame")->GetValueString();
00084     }
00085 
00086     this->updateRate = 100.0;
00087     if (!_sdf->HasElement("updateRate")) {
00088       ROS_WARN("OCPlugin (%s) missing <updateRate>, defaults to %f",
00089           this->modelNamespace.c_str(), this->updateRate);
00090     } else {
00091       this->updateRate = _sdf->GetElement("updateRate")->GetValueDouble();
00092     }
00093 
00094     this->mapTopic = "map";
00095     if (!_sdf->HasElement("mapTopic")) {
00096       ROS_WARN("OCPlugin (%s) missing <mapTopic>, defaults to \"%s\"",
00097           this->modelNamespace.c_str(), this->mapTopic.c_str());
00098     } else {
00099       this->mapTopic = _sdf->GetElement("mapTopic")->GetValueString();
00100     }
00101 
00102     this->modelRadius = 0.5;
00103     if (!_sdf->HasElement("modelRadius")) {
00104       ROS_WARN("OCPlugin (%s) missing <modelRadius>, defaults to %f",
00105           this->modelNamespace.c_str(), this->modelRadius);
00106     } else {
00107       this->modelRadius = _sdf->GetElement("modelRadius")->GetValueDouble();
00108     }
00109 
00110     this->modelPadding = 0.05;
00111     if (!_sdf->HasElement("modelPadding")) {
00112       ROS_WARN("OCPlugin (%s) missing <modelPadding>, defaults to %f",
00113           this->modelNamespace.c_str(), this->modelPadding);
00114     } else {
00115       this->modelPadding = _sdf->GetElement("modelPadding")->GetValueDouble();
00116     }
00117     this->circumscribed_model_distance_ = 
00118       this->modelPadding + this->modelRadius;
00119 
00120     timeout_period_ = 0.0;
00121 
00122     // Initialize update rate stuff
00123     if (this->updateRate > 0.0) {
00124       this->update_period_ = 1.0 / this->updateRate;
00125     } else {
00126       this->update_period_ = 0.0;
00127     }
00128     last_update_time_ = this->world->GetSimTime();
00129 
00130     // Initialize velocity stuff
00131     last_odom_pose_ = this->parent->GetWorldPose();
00132 
00133     x_ = 0;
00134     y_ = 0;
00135     rot_ = 0;
00136     alive_ = true;
00137 
00138     // Initialize the ROS node and subscribe to cmd_vel
00139     int argc = 0;
00140     char** argv = NULL;
00141     ros::init(argc, argv, "object_controller_plugin", 
00142         ros::init_options::NoSigintHandler | ros::init_options::AnonymousName);
00143     rosnode_ = new ros::NodeHandle(this->modelNamespace);
00144 
00145     ROS_DEBUG("OCPlugin (%s) has started!", 
00146         this->modelNamespace.c_str());
00147 
00148     tf_prefix_ = tf::getPrefixParam(*rosnode_);
00149     transform_broadcaster_ = new tf::TransformBroadcaster();
00150 
00151     // ROS: Subscribe to the velocity command topic (usually "cmd_vel")
00152     ros::SubscribeOptions so =
00153       ros::SubscribeOptions::create<geometry_msgs::Twist>(topicName, 1,
00154           boost::bind(&ObjectControllerPlugin::cmdVelCallback, this, _1),
00155           ros::VoidPtr(), &queue_);
00156 
00157     sub_ = rosnode_->subscribe(so);
00158 
00159     ROS_DEBUG("OCPlugin (%s) is subscribing to the map: %s", 
00160         this->modelNamespace.c_str(), 
00161         (rosnode_->resolveName(mapTopic)).c_str());
00162     ros::SubscribeOptions so2 =
00163       ros::SubscribeOptions::create<nav_msgs::OccupancyGrid>(mapTopic, 1,
00164           boost::bind(&ObjectControllerPlugin::getSimpleMap, this, _1),
00165           ros::VoidPtr(), &queue_);
00166     sub2_ = rosnode_->subscribe(so2);
00167     map_available_ = false;
00168 
00169     pub_ = rosnode_->advertise<nav_msgs::Odometry>("odom", 1);
00170     pub2_ = 
00171       rosnode_->advertise<nav_msgs::OccupancyGrid>("expanded_map", 1, true);
00172 
00173     ros::AdvertiseServiceOptions so3 = 
00174       ros::AdvertiseServiceOptions::create<segbot_gazebo_plugins::UpdatePluginState>(
00175           "update_state", 
00176           boost::bind(&ObjectControllerPlugin::updateState, this, _1, _2), 
00177           ros::VoidPtr(), &queue_
00178           );
00179 
00180     update_state_service_server_ = rosnode_->advertiseService(so3);
00181     pause_ = false;
00182 
00183     // start custom queue for diff drive
00184     this->callback_queue_thread_ = 
00185       boost::thread(boost::bind(&ObjectControllerPlugin::QueueThread, this));
00186 
00187     // listen to the update event (broadcast every simulation iteration)
00188     this->updateConnection = 
00189       event::Events::ConnectWorldUpdateStart(
00190           boost::bind(&ObjectControllerPlugin::UpdateChild, this));
00191 
00192   }
00193 
00194   // Update the controller
00195   void ObjectControllerPlugin::UpdateChild() {
00196     common::Time current_time = this->world->GetSimTime();
00197     double seconds_since_last_update = 
00198       (current_time - last_update_time_).Double();
00199     if (seconds_since_last_update > update_period_) {
00200       if (timeout_period_ != 0.0) {
00201         if ((current_time - time_of_last_message_).Double() > timeout_period_) {
00202           boost::mutex::scoped_lock scoped_lock(lock);
00203           x_ = y_ = rot_ = 0;
00204         }
00205       }
00206       boost::mutex::scoped_lock scoped_lock(state_lock_);
00207       if (!pause_) {
00208         writePositionData(seconds_since_last_update);
00209       }
00210       publishOdometry(seconds_since_last_update);
00211       last_update_time_+= common::Time(update_period_);
00212     }
00213   }
00214 
00215   // Finalize the controller
00216   void ObjectControllerPlugin::FiniChild() {
00217     alive_ = false;
00218     queue_.clear();
00219     queue_.disable();
00220     rosnode_->shutdown();
00221     callback_queue_thread_.join();
00222   }
00223 
00224   bool ObjectControllerPlugin::updateState(
00225       segbot_gazebo_plugins::UpdatePluginState::Request &req,
00226       segbot_gazebo_plugins::UpdatePluginState::Response &resp) {
00227 
00228     boost::mutex::scoped_lock scoped_lock(state_lock_);
00229     pause_ = req.pause;
00230 
00231     return true;
00232   }
00233 
00234   void ObjectControllerPlugin::cmdVelCallback(
00235       const geometry_msgs::Twist::ConstPtr& cmd_msg) {
00236     boost::mutex::scoped_lock scoped_lock(lock);
00237     time_of_last_message_ = this->world->GetSimTime();
00238     x_ = cmd_msg->linear.x;
00239     y_ = cmd_msg->linear.y;
00240     rot_ = cmd_msg->angular.z;
00241   }
00242 
00243   void ObjectControllerPlugin::QueueThread() {
00244     static const double timeout = 0.01;
00245     while (alive_ && rosnode_->ok()) {
00246       queue_.callAvailable(ros::WallDuration(timeout));
00247     }
00248   }
00249 
00250   void ObjectControllerPlugin::getSimpleMap(
00251       const nav_msgs::OccupancyGrid::ConstPtr& map) {
00252 
00253     ROS_DEBUG("OCPlugin (%s) has received a map.", 
00254         this->modelNamespace.c_str());
00255 
00256     map_.header = map->header;
00257 
00258     map_.info.map_load_time = map->info.map_load_time;
00259     map_.info.resolution = map->info.resolution;
00260     map_.info.width = map->info.width;
00261     map_.info.height = map->info.height;
00262 
00263     // Get the map origin in global space
00264     // useful for multi_level_map
00265     tf::TransformListener listener;
00266     geometry_msgs::PoseStamped pose_in, pose_out;
00267     pose_in.header = map->header;
00268     pose_in.pose = map->info.origin;
00269 
00270     map_.info.origin = pose_in.pose;
00271     // If the map is not in the gazebo global frame, acquire the transformation
00272     if (map->header.frame_id != this->globalFrame && 
00273         "/" + map->header.frame_id != this->globalFrame &&
00274         map->header.frame_id != "/" + this->globalFrame) {
00275       bool transform_available = 
00276         listener.waitForTransform(map->header.frame_id, 
00277             this->globalFrame, ros::Time(0), ros::Duration(5.0));
00278       if (transform_available) {
00279         ROS_INFO("OCPlugin (%s) Transformation to gazebo global frame acquired",
00280             this->modelNamespace.c_str());
00281         listener.transformPose(this->globalFrame, ros::Time(0), pose_in, 
00282             pose_in.header.frame_id, pose_out);
00283         map_.info.origin = pose_out.pose;
00284       } else {
00285         ROS_ERROR("OCPlugin (%s) Transformation to gazebo global frame failed", 
00286             this->modelNamespace.c_str());
00287         ROS_ERROR("OCPlugin (%s)   Failed transform is %s (global) to %s",
00288             this->modelNamespace.c_str(), this->globalFrame.c_str(),
00289             map->header.frame_id.c_str());
00290       }
00291     }
00292 
00293     // Expand the map out based on the circumscribed model distance
00294     int expand_pixels = 
00295       ceil(circumscribed_model_distance_ / map->info.resolution);
00296     map_.data.resize(map->info.height * map->info.width);
00297     for (int i = 0; i < (int)map->info.height; ++i) {
00298       for (int j = 0; j < (int)map->info.width; ++j) {
00299         int low_i = (i - expand_pixels < 0) ? 0 : i - expand_pixels;
00300         int high_i = (i + expand_pixels >= (int)map->info.height) ? 
00301           map->info.height - 1 : i + expand_pixels;
00302         int max = 0;
00303         for (int k = low_i; k <= high_i; ++k) {
00304           int diff_j = 
00305             floor(sqrtf(expand_pixels * expand_pixels - (i - k) * (i - k)));
00306           int low_j = (j - diff_j < 0) ? 0 : j - diff_j;
00307           int high_j = (j + diff_j >= (int)map->info.width) ? 
00308             map->info.width - 1 : j + diff_j;
00309           for (int l = low_j; l <= high_j; ++l) {
00310             if (map->data[k * map->info.width + l] > max) {
00311               max = map->data[k * map->info.width + l];
00312             }
00313           }
00314         }
00315         map_.data[i * map->info.width + j] = max;
00316       }
00317     }
00318 
00319     pub2_.publish(map_);
00320     map_available_ = true;
00321 
00322     ROS_DEBUG("OCPlugin (%s) has processed the map.", 
00323         this->modelNamespace.c_str());
00324   }
00325 
00326   void ObjectControllerPlugin::publishOdometry(double step_time) {
00327     ros::Time current_time = ros::Time::now();
00328     std::string odom_frame = tf::resolve(tf_prefix_, "odom");
00329     std::string base_footprint_frame = 
00330       tf::resolve(tf_prefix_, "base_footprint");
00331 
00332     // getting data for base_footprint to odom transform
00333     math::Pose pose = this->parent->GetWorldPose();
00334 
00335     tf::Quaternion qt(pose.rot.x, pose.rot.y, pose.rot.z, pose.rot.w);
00336     tf::Vector3 vt(pose.pos.x, pose.pos.y, pose.pos.z);
00337 
00338     tf::Transform base_footprint_to_odom(qt, vt);
00339     transform_broadcaster_->sendTransform(
00340         tf::StampedTransform(base_footprint_to_odom, current_time, odom_frame,
00341             base_footprint_frame));
00342 
00343     // publish odom topic
00344     odom_.pose.pose.position.x = pose.pos.x;
00345     odom_.pose.pose.position.y = pose.pos.y;
00346 
00347     odom_.pose.pose.orientation.x = pose.rot.x;
00348     odom_.pose.pose.orientation.y = pose.rot.y;
00349     odom_.pose.pose.orientation.z = pose.rot.z;
00350     odom_.pose.pose.orientation.w = pose.rot.w;
00351     odom_.pose.covariance[0] = 0.00001;
00352     odom_.pose.covariance[7] = 0.00001;
00353     odom_.pose.covariance[14] = 1000000000000.0;
00354     odom_.pose.covariance[21] = 1000000000000.0;
00355     odom_.pose.covariance[28] = 1000000000000.0;
00356     odom_.pose.covariance[35] = 0.001;
00357 
00358     // get velocity in /odom frame
00359     math::Vector3 linear;
00360     // Getting values from the worlds model in gazebo instead of supplied
00361     // velocites as a simple means of error correction
00362     linear.x = (pose.pos.x - last_odom_pose_.pos.x) / step_time;
00363     linear.y = (pose.pos.y - last_odom_pose_.pos.y) / step_time;
00364     boost::mutex::scoped_lock scoped_lock(lock);
00365     if (rot_ > M_PI / step_time) { 
00366       // we cannot calculate the angular velocity correctly
00367       odom_.twist.twist.angular.z = rot_;
00368     } else {
00369       float last_yaw = last_odom_pose_.rot.GetYaw();
00370       float current_yaw = pose.rot.GetYaw();
00371       while (current_yaw < last_yaw - M_PI) current_yaw += 2*M_PI;
00372       while (current_yaw > last_yaw + M_PI) current_yaw -= 2*M_PI;
00373       float angular_diff = current_yaw - last_yaw;
00374       odom_.twist.twist.angular.z = angular_diff / step_time;
00375     }
00376     last_odom_pose_ = pose;
00377 
00378     // convert velocity to child_frame_id (aka base_footprint)
00379     float yaw = pose.rot.GetYaw();
00380     odom_.twist.twist.linear.x = cosf(yaw) * linear.x + sinf(yaw) * linear.y;
00381     odom_.twist.twist.linear.y = cosf(yaw) * linear.y - sinf(yaw) * linear.x;
00382 
00383     odom_.header.stamp = current_time;
00384     odom_.header.frame_id = odom_frame;
00385     odom_.child_frame_id = base_footprint_frame;
00386 
00387     pub_.publish(odom_);
00388   }
00389 
00390   // Update the data in the interface
00391   void ObjectControllerPlugin::writePositionData(double step_time) {
00392     // move the simple model manually
00393     if (map_available_) {
00394 
00395       boost::mutex::scoped_lock scoped_lock(lock);
00396       float dr = x_ * step_time;
00397       float dy = y_ * step_time;
00398       float da = rot_ * step_time;
00399 
00400       if (fabs(dr) < 1e-3 && fabs(dy) < 1e-3 && fabs(da) < 1e-3) {
00401         // Don't keep overwriting in case the user wants to try and move a
00402         // stationary object. This plugin moving the object around can create
00403         // some problems
00404         return;
00405       }
00406 
00407       math::Pose orig_pose = this->parent->GetWorldPose();
00408       math::Pose new_pose = orig_pose;
00409       new_pose.pos.x = orig_pose.pos.x + 
00410         dr * cos(orig_pose.rot.GetYaw()) - dy * sin(orig_pose.rot.GetYaw());
00411       new_pose.pos.y = orig_pose.pos.y + 
00412         dr * sin(orig_pose.rot.GetYaw()) + dy * cos(orig_pose.rot.GetYaw());
00413       new_pose.rot.SetFromEuler(math::Vector3(0,0,orig_pose.rot.GetYaw() + da));
00414 
00415       // Check if the new pose can be allowed
00416       int x_pxl = 
00417         (new_pose.pos.x - map_.info.origin.position.x) / map_.info.resolution;
00418       int y_pxl = 
00419         (new_pose.pos.y - map_.info.origin.position.y) / map_.info.resolution;
00420 
00421       if (x_pxl < 0 || x_pxl >= (int)map_.info.width ||
00422           y_pxl < 0 || y_pxl >= (int)map_.info.height ||
00423           (map_.data[y_pxl * map_.info.width + x_pxl] < 50)) {
00424         this->parent->SetWorldPose(new_pose);
00425         math::Vector3 zeros(0,0,0);
00426         this->parent->SetLinearVel(zeros);
00427         this->parent->SetLinearAccel(zeros);
00428         this->parent->SetAngularVel(zeros);
00429         this->parent->SetAngularAccel(zeros);
00430       } else {
00431         ROS_DEBUG_THROTTLE(2.0, "OCPlugin (%s) is preventing the object from "
00432             "running into a wall.", this->modelNamespace.c_str());
00433       } 
00434     } else {
00435       ROS_WARN_THROTTLE(2.0, "OCPlugin (%s) has not received a map. " 
00436           "Cannot move the object", this->modelNamespace.c_str());
00437     }
00438 
00439   }
00440 
00441   GZ_REGISTER_MODEL_PLUGIN(ObjectControllerPlugin)
00442 }
00443 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


segbot_gazebo_plugins
Author(s): Piyush Khandelwal
autogenerated on Mon Aug 5 2013 12:10:02