00001 /****************************************************************************** 00002 STDR Simulator - Simple Two DImensional Robot Simulator 00003 Copyright (C) 2013 STDR Simulator 00004 This program is free software; you can redistribute it and/or modify 00005 it under the terms of the GNU General Public License as published by 00006 the Free Software Foundation; either version 3 of the License, or 00007 (at your option) any later version. 00008 This program is distributed in the hope that it will be useful, 00009 but WITHOUT ANY WARRANTY; without even the implied warranty of 00010 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00011 GNU General Public License for more details. 00012 You should have received a copy of the GNU General Public License 00013 along with this program; if not, write to the Free Software Foundation, 00014 Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA 00015 00016 Authors: 00017 00018 Oscar Lima Carrion, olima_84@yahoo.com 00019 Ashok Meenakshi, mashoksc@gmail.com 00020 Seguey Alexandrov, sergeyalexandrov@mail.com 00021 00022 Review / Edits: 00023 Manos Tsardoulias, etsardou@gmail.com 00024 00025 About this code: 00026 00027 This class represents a motion model for omnidirectional robot and could be 00028 used to sample the possible pose given the starting pose and the commanded 00029 robot's motion. 00030 00031 The motion is decomposed into two translations alond the x axis of the 00032 robot (forward), and along the y axis of the robot (lateral), and one 00033 rotation. 00034 ******************************************************************************/ 00035 00036 #ifndef OMNI_MOTION_CONTROLLER_H 00037 #define OMNI_MOTION_CONTROLLER_H 00038 00039 #include <stdr_robot/motion/motion_controller_base.h> 00040 00045 namespace stdr_robot 00046 { 00047 00053 class OmniMotionController : public MotionController 00054 { 00055 00056 public: 00057 00066 OmniMotionController( 00067 const geometry_msgs::Pose2D& pose, 00068 tf::TransformBroadcaster& tf, 00069 ros::NodeHandle& n, 00070 const std::string& name, 00071 const stdr_msgs::KinematicMsg params); 00072 00078 void calculateMotion(const ros::TimerEvent& event); 00079 00084 ~OmniMotionController(void); 00085 }; 00086 } 00087 00088 00089 #endif