cob_linear_nav.cpp
Go to the documentation of this file.
00001 /****************************************************************
00002  *
00003  * Copyright (c) 2010
00004  *
00005  * Fraunhofer Institute for Manufacturing Engineering   
00006  * and Automation (IPA)
00007  *
00008  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00009  *
00010  * Project name: care-o-bot
00011  * ROS stack name: cob_navigation
00012  * ROS package name: cob_navigation_linear
00013  *                                                              
00014  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00015  *                      
00016  * Author: Philipp Koehler, email:Philipp.Koehler@ipa.fhg.de
00017  *
00018  * Date of creation: Apr 2011
00019  * Date of major change: Apr 2012
00020  * Changes performed by: Matthias Gruhler, Matthias.Gruhler@ipa.fhg.de
00021  * ToDo:
00022  *
00023  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00024  *
00025  * Redistribution and use in source and binary forms, with or without
00026  * modification, are permitted provided that the following conditions are met:
00027  *
00028  *       * Redistributions of source code must retain the above copyright
00029  *               notice, this list of conditions and the following disclaimer.
00030  *       * Redistributions in binary form must reproduce the above copyright
00031  *               notice, this list of conditions and the following disclaimer in the
00032  *               documentation and/or other materials provided with the distribution.
00033  *       * Neither the name of the Fraunhofer Institute for Manufacturing 
00034  *               Engineering and Automation (IPA) nor the names of its
00035  *               contributors may be used to endorse or promote products derived from
00036  *               this software without specific prior written permission.
00037  *
00038  * This program is free software: you can redistribute it and/or modify
00039  * it under the terms of the GNU Lesser General Public License LGPL as 
00040  * published by the Free Software Foundation, either version 3 of the 
00041  * License, or (at your option) any later version.
00042  * 
00043  * This program is distributed in the hope that it will be useful,
00044  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00045  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
00046  * GNU Lesser General Public License LGPL for more details.
00047  * 
00048  * You should have received a copy of the GNU Lesser General Public 
00049  * License LGPL along with this program. 
00050  * If not, see <http://www.gnu.org/licenses/>.
00051  *
00052  ****************************************************************/
00053 
00054 //##################
00055 //#### includes ####
00056 
00057 // standard includes
00058 //--
00059 
00060 // ROS includes
00061 #include <ros/ros.h>
00062 #include <XmlRpc.h>
00063 
00064 #include <pthread.h>
00065 
00066 // ROS message includes
00067 #include <actionlib/client/simple_action_client.h>
00068 #include <actionlib/server/simple_action_server.h>
00069 #include <move_base_msgs/MoveBaseAction.h>
00070 
00071 #include <geometry_msgs/Twist.h>
00072 #include <geometry_msgs/PoseStamped.h>
00073 #include <nav_msgs/Odometry.h>
00074 
00075 #include <tf/transform_listener.h>
00076 
00077 //####################
00078 //#### node class ####
00079 class NodeClass
00080 {
00081         public:
00082         // create a handle for this node, initialize node
00083         ros::NodeHandle nh_;
00084                 
00085         // declaration of topics
00086         ros::Publisher topic_pub_command_, action_goal_pub_;
00087 
00088         ros::Subscriber goal_sub_, odometry_sub_;
00089         
00090         // declaration of action server
00091         actionlib::SimpleActionServer<move_base_msgs::MoveBaseAction> as_;
00092         move_base_msgs::MoveBaseResult result_; //result is of type geometry_msgs/PoseStamped
00093         
00094         //declaration of action client to forward move_base_simple messages
00095         actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> * action_client_;
00096         
00097 
00098         // Constructor
00099         NodeClass(std::string name) :
00100                 as_(nh_, name, boost::bind(&NodeClass::actionCB, this, _1), false)
00101         {                       
00102                 m_mutex = PTHREAD_MUTEX_INITIALIZER;
00103 
00104     ros::NodeHandle private_nh("~");    
00105 
00106                 // implementation of topics to publish
00107                 topic_pub_command_ = nh_.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00108                 
00109                 //we'll provide a mechanism for some people to send goals as PoseStamped messages over a topic
00110                 //they won't get any useful information back about its status, but this is useful for tools
00111                 //like nav_view and rviz
00112                 ros::NodeHandle simple_nh("move_base_linear_simple");
00113                 goal_sub_ = simple_nh.subscribe<geometry_msgs::PoseStamped>("goal", 1, boost::bind(&NodeClass::topicCB, this, _1));
00114 
00115                 action_client_ = new actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction>(nh_, name);
00116                 
00117                 // subscribe to odometry
00118                 odometry_sub_ = nh_.subscribe<nav_msgs::Odometry>("odom", 1, boost::bind(&NodeClass::odometryCB, this, _1));
00119 
00120                 // read parameters from parameter server
00121                 if(!private_nh.hasParam("kv")) ROS_WARN("Used default parameter for kv [2.5]");
00122                 private_nh.param("kv", kv_, 2.5);
00123 
00124                 if(!private_nh.hasParam("kp")) ROS_WARN("Used default parameter for kp [3.0]");
00125                 private_nh.param("kp", kp_, 3.0);
00126 
00127     if(!private_nh.hasParam("virt_mass")) ROS_WARN("Used default parameter for virt_mass [0.5]");
00128                 private_nh.param("virt_mass", virt_mass_, 0.5);
00129 
00130     if(!private_nh.hasParam("vmax")) ROS_WARN("Used default parameter for vmax [0.3 m/s]");
00131                 private_nh.param("vmax", v_max_, 0.3);
00132 
00133                 if(!private_nh.hasParam("goal_threshold")) ROS_WARN("Used default parameter for goal_threshold [0.03 cm]");
00134                 private_nh.param("goal_threshold", goal_threshold_, 0.03);
00135 
00136                 if(!private_nh.hasParam("speed_threshold")) ROS_WARN("Used default parameter for speed_threshold [0.08 m/s]");
00137                 private_nh.param("speed_threshold", speed_threshold_, 0.08);
00138                 
00139                 if(!private_nh.hasParam("kv_rot")) ROS_WARN("Used default parameter for kv_rot [2.0]");
00140                 private_nh.param("kv_rot", kv_rot_, 2.0);
00141 
00142                 if(!private_nh.hasParam("kp_rot")) ROS_WARN("Used default parameter for kp_rot [2.0]");
00143                 private_nh.param("kp_rot", kp_rot_, 2.0);
00144 
00145     if(!private_nh.hasParam("virt_mass_rot")) ROS_WARN("Used default parameter for virt_mass_rot [0.5]");
00146                 private_nh.param("virt_mass_rot", virt_mass_rot_, 0.5);
00147                                 
00148                 if(!private_nh.hasParam("vtheta_max")) ROS_WARN("Used default parameter for vtheta_max [0.3 rad/s]");
00149                 private_nh.param("vtheta_max", vtheta_max_, 0.3);
00150                 
00151                 if(!private_nh.hasParam("goal_threshold_rot")) ROS_WARN("Used default parameter for goal_threshold_rot [0.08 rad]");
00152                 private_nh.param("goal_threshold_rot", goal_threshold_rot_, 0.08);
00153                 
00154                 if(!private_nh.hasParam("speed_threshold_rot")) ROS_WARN("Used default parameter for speed_threshold_rot [0.08 rad/s]");
00155                 private_nh.param("speed_threshold_rot", speed_threshold_rot_, 0.08);
00156                 
00157                 if(!private_nh.hasParam("global_frame")) ROS_WARN("Used default parameter for global_frame [/map]");
00158                 private_nh.param("global_frame", global_frame_, std::string("/map"));
00159                 
00160                 if(!private_nh.hasParam("robot_frame")) ROS_WARN("Used default parameter for robot_frame [/base_link]");
00161                 private_nh.param("robot_frame", robot_frame_, std::string("/base_link"));
00162 
00163                 if(!private_nh.hasParam("slow_down_distance")) ROS_WARN("Used default parameter for slow_down_distance [0.5m]");
00164                 private_nh.param("slow_down_distance", slow_down_distance_, 0.5);
00165 
00166                 if(!private_nh.hasParam("goal_abortion_time")) ROS_WARN("Used default parameter for goal_abortion_time [5.0s]");
00167                 private_nh.param("goal_abortion_time", goal_abortion_time_, 5.0);
00168 
00169     //generate robot zero_pose
00170                 zero_pose_.pose.position.x = 0.0;
00171                 zero_pose_.pose.position.y = 0.0;
00172                 zero_pose_.pose.position.z = 0.0;
00173                 zero_pose_.pose.orientation = tf::createQuaternionMsgFromYaw(0.0);
00174                 zero_pose_.header.frame_id = robot_frame_;
00175 
00176                 //we need to make sure that the transform between the robot base frame and the global frame is available
00177                 ros::Time last_error = ros::Time::now();
00178                 std::string tf_error;
00179                 while(!tf_listener_.waitForTransform(global_frame_, robot_frame_, ros::Time(), ros::Duration(0.1), ros::Duration(0.01), &tf_error)) {
00180                         ros::spinOnce();
00181                         if(last_error + ros::Duration(5.0) < ros::Time::now()){
00182                                 ROS_WARN("Waiting on transform from %s to %s to become available before running cob_linear_nav, tf error: %s", 
00183                                 robot_frame_.c_str(), global_frame_.c_str(), tf_error.c_str());
00184                                 last_error = ros::Time::now();
00185                         }
00186                 }
00187                 
00188                 //start action server, it holds the main loop while driving
00189                 as_.start();
00190         }
00191         
00192         void topicCB(const geometry_msgs::PoseStamped::ConstPtr& goal){
00193                 ROS_INFO("In ROS goal callback, wrapping the PoseStamped in the action message and re-sending to the server.");
00194                 move_base_msgs::MoveBaseGoal action_goal;
00195                 action_goal.target_pose = *goal;
00196 
00197                 action_client_->sendGoal(action_goal);
00198                 action_client_->stopTrackingGoal();
00199         }
00200         
00201         void actionCB(const move_base_msgs::MoveBaseGoalConstPtr &goal){
00202     // goal is of type geometry_msgs/PoseStamped
00203                 ROS_INFO("In idle mode, new goal accepted");
00204 
00205     last_time_moving_ = ros::Time::now().toSec();
00206 
00207     getRobotPoseGlobal();
00208                 x_last_ = robot_pose_global_.pose.position.x;
00209                 y_last_ = robot_pose_global_.pose.position.y;
00210                 theta_last_ = tf::getYaw(robot_pose_global_.pose.orientation);
00211                 vtheta_last_ = 0.0f;
00212                 vx_last_ = 0.0f;
00213                 vy_last_ = 0.0f;
00214                 last_time_ = ros::Time::now().toSec();
00215                 
00216                 goal_pose_global_ = transformGoalToMap(goal->target_pose);
00217                 
00218                 move_ = true;
00219                 
00220                 ros::Rate loop_rate(100);
00221                 while(nh_.ok()) {
00222                         loop_rate.sleep();
00223 
00224                         if(as_.isPreemptRequested()) {
00225                                 if(as_.isNewGoalAvailable()) {
00226                                         ROS_INFO("New goal received, updating movement");
00227                                         //if we're active and a new goal is available, we'll accept it
00228                                         move_base_msgs::MoveBaseGoal new_goal = * as_.acceptNewGoal();
00229                                         goal_pose_global_ = transformGoalToMap(new_goal.target_pose);
00230 
00231           last_time_moving_ = ros::Time::now().toSec();
00232                                         move_ = true;
00233                                 } else {
00234                                         ROS_INFO("Preempt requested, aborting movement");
00235                                         //notify the ActionServer that we've successfully preempted
00236                                         as_.setPreempted();
00237                                         
00238                                         move_ = false;
00239                                         stopMovement();
00240                                         return;
00241                                 }
00242                         }
00243                         
00244                         performControllerStep();
00245                         
00246                         if(finished_) {
00247                                 as_.setSucceeded(move_base_msgs::MoveBaseResult(), "Goal reached.");
00248                                 ROS_INFO("Goal reached.");
00249                                 return;
00250                         }
00251 
00252       if(!as_.isActive()) {
00253         ROS_INFO("Goal not active anymore. Stop!");
00254         return;
00255       }
00256                 }
00257                 
00258                 
00259                 //if the node is killed then we'll abort and return
00260                 stopMovement();
00261                 as_.setAborted(move_base_msgs::MoveBaseResult(), "Aborting on the goal because the node has been killed");
00262                 return;
00263         };
00264 
00265 
00266         void odometryCB(const nav_msgs::Odometry::ConstPtr &odometry){ 
00267                 geometry_msgs::Vector3Stamped vec_stamped;
00268                 
00269                 vec_stamped.vector = odometry->twist.twist.linear;
00270                 vec_stamped.header.frame_id =  "/base_footprint";
00271                 tf_listener_.transformVector(robot_frame_, vec_stamped, robot_twist_linear_robot_);
00272                 
00273                 vec_stamped.vector = odometry->twist.twist.angular;
00274                 vec_stamped.header.frame_id =  "/base_footprint";
00275                 tf_listener_.transformVector(robot_frame_, vec_stamped, robot_twist_angular_robot_);
00276         }
00277         
00278         // Destructor
00279         ~NodeClass() 
00280         {
00281         }
00282         
00283         private:
00284         tf::TransformListener tf_listener_;
00285         std::string global_frame_, robot_frame_;
00286         geometry_msgs::PoseStamped goal_pose_global_;
00287         geometry_msgs::PoseStamped zero_pose_;
00288         geometry_msgs::PoseStamped robot_pose_global_;
00289         geometry_msgs::Vector3Stamped robot_twist_linear_robot_, robot_twist_angular_robot_;
00290         
00291   double slow_down_distance_, goal_abortion_time_;
00292         
00293         bool finished_, move_;
00294         
00295         pthread_mutex_t m_mutex;
00296         
00297         //core functions:
00298         void performControllerStep();
00299         void publishVelocitiesGlobal(double vx, double vy, double theta);
00300         geometry_msgs::PoseStamped transformGoalToMap(geometry_msgs::PoseStamped goal_pose);
00301         geometry_msgs::PoseStamped getRobotPoseGlobal();
00302 
00303         //helper functions:
00304         double getDistance2d(geometry_msgs::PoseStamped a, geometry_msgs::PoseStamped b);
00305         double getDistance2d(geometry_msgs::Point a, geometry_msgs::Point b);
00306         double getThetaDiffRad(double target, double actual);
00307         double sign(double x);
00308         void stopMovement();
00309   bool notMovingDueToObstacle();
00310         
00311         //Potential field Controller variables
00312         double vx_last_, vy_last_, x_last_, y_last_, theta_last_, vtheta_last_;
00313         double goal_threshold_, speed_threshold_;
00314         double goal_threshold_rot_, speed_threshold_rot_;
00315         double kp_, kv_, virt_mass_;
00316         double kp_rot_, kv_rot_, virt_mass_rot_;
00317         double last_time_;
00318         double v_max_, vtheta_max_;
00319   double last_time_moving_;
00320 
00321 }; //NodeClass
00322 
00323 geometry_msgs::PoseStamped NodeClass::transformGoalToMap(geometry_msgs::PoseStamped goal_pose) {
00324         geometry_msgs::PoseStamped goal_global_;
00325         if(goal_pose.header.frame_id == global_frame_) return goal_pose;
00326         else if(tf_listener_.canTransform(global_frame_, goal_pose.header.frame_id, ros::Time(0), new std::string)) {
00327                 tf_listener_.transformPose(global_frame_, goal_pose, goal_global_);
00328                 return goal_global_;
00329         } else {
00330                 ROS_WARN("Can't transform goal to global frame %s", global_frame_.c_str());
00331                 return robot_pose_global_;
00332         }
00333 }
00334 
00335 geometry_msgs::PoseStamped NodeClass::getRobotPoseGlobal() {
00336         try{
00337                 tf_listener_.transformPose(global_frame_, zero_pose_, robot_pose_global_);
00338         }
00339         catch(tf::TransformException& ex){
00340                 ROS_WARN("Failed to find robot pose in global frame %s", global_frame_.c_str());
00341                 return zero_pose_;
00342         }
00343         
00344         return robot_pose_global_;
00345 }
00346 
00347 double NodeClass::getDistance2d(geometry_msgs::PoseStamped a, geometry_msgs::PoseStamped b) {
00348         return sqrt( pow(a.pose.position.x - b.pose.position.x,2) + pow(a.pose.position.y - b.pose.position.y,2) );
00349 }
00350 
00351 double NodeClass::getDistance2d(geometry_msgs::Point a, geometry_msgs::Point b) {
00352         return sqrt( pow(a.x - b.x,2) + pow(a.y - b.y,2) );
00353 }
00354 
00355 double NodeClass::sign(double x) {
00356         if(x >= 0.0f) return 1.0f;
00357         else return -1.0f;
00358 }
00359 
00360 double NodeClass::getThetaDiffRad(double target, double actual) {
00361         if(fabs(target - actual) <= M_PI) return (target - actual);
00362         else return sign(target - actual) * -2.0f * M_PI - (target - actual);
00363 }
00364 
00365 void NodeClass::publishVelocitiesGlobal(double vx, double vy, double theta) {
00366         //Transform commands from global frame to robot coordinate system
00367         geometry_msgs::Vector3Stamped cmd_global, cmd_robot;
00368         geometry_msgs::Twist msg;
00369         
00370         cmd_global.header.frame_id = global_frame_;
00371         cmd_global.vector.x = vx;
00372         cmd_global.vector.y = vy;
00373         try { tf_listener_.transformVector(robot_frame_, cmd_global, cmd_robot);
00374         } catch (tf::TransformException ex){
00375                 ROS_ERROR("%s",ex.what());
00376                 cmd_robot.vector.x = 0.0f;
00377                 cmd_robot.vector.y = 0.0f;
00378         }
00379         
00380         
00381         msg.linear = cmd_robot.vector;
00382         msg.angular.z = theta;
00383         msg.linear.z = 0.0; msg.angular.x = 0.0; msg.angular.y = 0.0;
00384         
00385         topic_pub_command_.publish(msg);
00386 }
00387 
00388 void NodeClass::stopMovement() {
00389         publishVelocitiesGlobal(0.0f, 0.0f, 0.0f);
00390         vx_last_ = 0.0f;
00391         vy_last_ = 0.0f;
00392         vtheta_last_ = 0.0f;
00393 }
00394 
00395 bool NodeClass::notMovingDueToObstacle() {
00396   if (move_ == true && // should move
00397       finished_ == false && // has not reached goal
00398       fabs(robot_twist_linear_robot_.vector.x) <= 0.01 && // velocity components are small
00399       fabs(robot_twist_linear_robot_.vector.y) <= 0.01 &&
00400       fabs(robot_twist_angular_robot_.vector.z) <= 0.01 &&
00401       ros::Time::now().toSec() - last_time_moving_ > goal_abortion_time_ ) // has not been moving for x seconds
00402   {
00403     return true;
00404   } else if ( fabs(robot_twist_linear_robot_.vector.x) > 0.01 ||
00405               fabs(robot_twist_linear_robot_.vector.y) > 0.01 ||
00406               fabs(robot_twist_angular_robot_.vector.z) > 0.01 )
00407   { // still moving, then update last_time_moving_
00408     last_time_moving_ = ros::Time::now().toSec();
00409   }
00410 
00411   return false;
00412    
00413 }
00414 
00415 void NodeClass::performControllerStep() {
00416         pthread_mutex_lock(&m_mutex);
00417 
00418         double dt;
00419         double F_x, F_y, F_theta;
00420   double distance_to_goal;
00421   double theta, theta_goal;
00422         double cmd_vx, cmd_vy, cmd_vtheta;
00423         double vx_d, vy_d, vtheta_d, v_factor;
00424   double v_max_goal = v_max_;
00425 
00426         if(!move_) {
00427                 pthread_mutex_unlock(&m_mutex);
00428                 return;
00429         }
00430         
00431         getRobotPoseGlobal();
00432 
00433   distance_to_goal = getDistance2d(robot_pose_global_, goal_pose_global_);
00434         theta = tf::getYaw(robot_pose_global_.pose.orientation);
00435         theta_goal = tf::getYaw(goal_pose_global_.pose.orientation);
00436         
00437         //exit, if positions and velocities lie inside thresholds
00438         if( distance_to_goal <= goal_threshold_ &&
00439       sqrt(vx_last_ * vx_last_ + vy_last_ * vy_last_) <= speed_threshold_ &&
00440       fabs(getThetaDiffRad(theta_goal, theta)) <= goal_threshold_rot_ &&
00441       fabs(vtheta_last_) <= speed_threshold_rot_ )
00442         {
00443                 finished_ = true;
00444                 move_ = false;
00445                 stopMovement();
00446                 pthread_mutex_unlock(&m_mutex);
00447                 return;
00448         } else if( notMovingDueToObstacle() == true ) {
00449                 finished_ = false;
00450                 move_ = false;
00451                 stopMovement();
00452     as_.setAborted(move_base_msgs::MoveBaseResult(), "Cancel the goal because an obstacle is blocking the path.");
00453     ROS_INFO("Cancel the goal because an obstacle is blocking the path.");
00454                 pthread_mutex_unlock(&m_mutex);
00455                 return;
00456         } else finished_ = false;
00457 
00458         dt = ros::Time::now().toSec() - last_time_;
00459         last_time_ = ros::Time::now().toSec();
00460 
00461         //Slow down while approaching goal
00462         if(distance_to_goal < slow_down_distance_) {
00463                 //implementation for linear decrease of v_max:
00464                 double goal_linear_slope = v_max_ / slow_down_distance_;
00465                 v_max_goal = distance_to_goal * goal_linear_slope;
00466 
00467                 if(v_max_goal > v_max_) v_max_goal = v_max_;
00468                         else if(v_max_goal < 0.0f) v_max_goal = 0.0f;
00469         }
00470         
00471         //Translational movement
00472         //calculation of v factor to limit maxspeed
00473         vx_d = kp_/kv_ * (goal_pose_global_.pose.position.x - robot_pose_global_.pose.position.x);
00474         vy_d = kp_/kv_ * (goal_pose_global_.pose.position.y - robot_pose_global_.pose.position.y);
00475         v_factor = v_max_goal / sqrt(vy_d*vy_d + vx_d*vx_d);
00476 
00477         if(v_factor > 1.0) v_factor = 1.0;
00478         
00479         F_x = - kv_ * vx_last_ + v_factor * kp_ * (goal_pose_global_.pose.position.x - robot_pose_global_.pose.position.x);
00480         F_y = - kv_ * vy_last_ + v_factor * kp_ * (goal_pose_global_.pose.position.y - robot_pose_global_.pose.position.y);
00481 
00482         cmd_vx = vx_last_ + F_x / virt_mass_ * dt;
00483         cmd_vy = vy_last_ + F_y / virt_mass_ * dt;
00484 
00485         //Rotational Movement
00486         //calculation of v factor to limit maxspeed
00487         vtheta_d = kp_rot_ / kv_rot_ * getThetaDiffRad(theta_goal, theta);
00488         v_factor = fabs(vtheta_max_ / vtheta_d);
00489         if(v_factor > 1.0) v_factor = 1.0;
00490         
00491         F_theta = - kv_rot_ * vtheta_last_ + v_factor * kp_rot_ * getThetaDiffRad(theta_goal, theta);
00492         cmd_vtheta = vtheta_last_ + F_theta / virt_mass_rot_ * dt;
00493 
00494         //Publish velocities, these calculated forces and velocities are for the global frame
00495   //they are transformed to robot_frame later
00496         x_last_ = robot_pose_global_.pose.position.x;
00497         y_last_ = robot_pose_global_.pose.position.y;
00498         theta_last_ = theta;
00499         vx_last_ = cmd_vx;
00500         vy_last_ = cmd_vy;
00501         vtheta_last_ = cmd_vtheta;
00502 
00503         publishVelocitiesGlobal(cmd_vx, cmd_vy, cmd_vtheta);
00504         pthread_mutex_unlock(&m_mutex);
00505 }
00506 
00507 
00508 
00509 //#######################
00510 //#### main programm ####
00511 int main(int argc, char** argv)
00512 {
00513         // initialize ROS, spezify name of node
00514         ros::init(argc, argv, "cob_linear");
00515         
00516         // create nodeClass
00517         NodeClass nodeClass("move_base_linear");
00518 
00519         ros::spin();
00520 
00521         return 0;
00522 }
00523 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


cob_linear_nav
Author(s): Philipp Koehler
autogenerated on Fri Mar 1 2013 17:51:24