edge_dynamic_obstacle.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2016,
00006  *  TU Dortmund - Institute of Control Theory and Systems Engineering.
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the institute nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  * 
00036  * Notes:
00037  * The following class is derived from a class defined by the
00038  * g2o-framework. g2o is licensed under the terms of the BSD License.
00039  * Refer to the base class source for detailed licensing information.
00040  *
00041  * Author: Christoph Rösmann
00042  *********************************************************************/
00043 
00044 #ifndef EDGE_DYNAMICOBSTACLE_H
00045 #define EDGE_DYNAMICOBSTACLE_H
00046 
00047 #include <teb_local_planner/g2o_types/vertex_pose.h>
00048 #include <teb_local_planner/g2o_types/vertex_timediff.h>
00049 #include <teb_local_planner/g2o_types/penalties.h>
00050 #include <teb_local_planner/obstacles.h>
00051 #include <teb_local_planner/teb_config.h>
00052 
00053 #include "g2o/core/base_binary_edge.h"
00054 
00055 namespace teb_local_planner
00056 {
00057   
00071 class EdgeDynamicObstacle : public g2o::BaseBinaryEdge<1, const Obstacle*, VertexPose, VertexTimeDiff>
00072 {
00073 public:
00074   
00078   EdgeDynamicObstacle() : vert_idx_(0)
00079   {
00080     _vertices[0] = _vertices[1] = NULL;
00081   }
00082   
00087   EdgeDynamicObstacle(size_t vert_idx) : vert_idx_(vert_idx)
00088   {
00089     _vertices[0] = _vertices[1] = NULL;
00090   }
00091   
00098   virtual ~EdgeDynamicObstacle() 
00099   {
00100     if(_vertices[0]) _vertices[0]->edges().erase(this);
00101     if(_vertices[1]) _vertices[1]->edges().erase(this);
00102   }
00103 
00107   void computeError()
00108   {
00109     ROS_ASSERT_MSG(cfg_, "You must call setTebConfig on EdgeDynamicObstacle()");
00110     const VertexPose* bandpt = static_cast<const VertexPose*>(_vertices[0]);
00111     const VertexTimeDiff* dt_vertex = static_cast<const VertexTimeDiff*>(_vertices[1]);
00112     
00113     // WARNING: vert_idx_*dt is just an approximation for the total time, since we don't have a uniform dt at the moment!
00114     Eigen::Vector2d pred_obst_point = _measurement->getCentroid() + double(vert_idx_)*dt_vertex->estimate()*_measurement->getCentroidVelocity();
00115     double dist = (pred_obst_point - bandpt->position()).norm();
00116     /*
00117     // get point in x-y-t
00118     Eigen::Vector3d point(bandpt->estimate().coeffRef(0), bandpt->estimate().coeffRef(1), _vert_idx*dt_vertex->estimate());
00119     
00120     // calc distance of that point to the obstacle trajectory in x-y-t predicted with a constant velocity
00121     Eigen::Vector3d robot_point;
00122     robot_point.head(2) = _measurement->getCentroid();
00123     robot_point.coeffRef(2) = 0;
00124     Eigen::Vector3d robot_vel;
00125     robot_vel.head(2) = _measurement->getCentroidVelocity();
00126     robot_vel.coeffRef(2) = 1;
00127     double dist = 0; //calcDistancePointToLine<Eigen::Vector3d>(point, robot_point, robot_vel);   
00128     */ 
00129     
00130     _error[0] = penaltyBoundFromBelow(dist, cfg_->obstacles.min_obstacle_dist, cfg_->optim.penalty_epsilon);
00131 
00132     ROS_ASSERT_MSG(std::isfinite(_error[0]), "EdgeDynamicObstacle::computeError() _error[0]=%f _error[1]=%f\n",_error[0],_error[1]);      
00133   }
00134 
00141   ErrorVector& getError()
00142   {
00143     computeError();
00144     return _error;
00145   }
00146   
00150   virtual bool read(std::istream& is)
00151   {
00152     //  is >> _measurement[0];
00153     return true;
00154   }
00155 
00159   virtual bool write(std::ostream& os) const
00160   {
00161     //  os << information()(0,0) << " Error: " << _error[0] << ", Measurement X: " << _measurement[0] << ", Measurement Y: " << _measurement[1];
00162     return os.good();
00163   }
00164   
00169   void setVertexIdx(size_t vert_idx)
00170   {
00171     vert_idx_ = vert_idx;
00172   }
00173   
00178   void setObstacle(const Obstacle* obstacle)
00179   {
00180     _measurement = obstacle;
00181   }
00182   
00187   void setTebConfig(const TebConfig& cfg)
00188   {
00189     cfg_ = &cfg;
00190   }
00191 
00192 protected:
00193   
00194   const TebConfig* cfg_; 
00195   size_t vert_idx_; 
00196   
00197 public: 
00198   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00199 
00200 };
00201     
00202  
00203     
00204 
00205 } // end namespace
00206 
00207 #endif


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Mon Oct 24 2016 05:31:15