motion_controller_base.h
Go to the documentation of this file.
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    * Manos Tsardoulias, etsardou@gmail.com
00018    * Aris Thallas, aris.thallas@gmail.com
00019    * Chris Zalidis, zalidis@gmail.com 
00020 ******************************************************************************/
00021 
00022 #ifndef MOTION_CONTROLLER_BASE_H
00023 #define MOTION_CONTROLLER_BASE_H
00024 
00025 #include <ros/ros.h>
00026 #include <tf/transform_broadcaster.h>
00027 #include <geometry_msgs/Twist.h>
00028 #include <geometry_msgs/Pose2D.h>
00029 
00034 namespace stdr_robot {
00035     
00040   class MotionController {
00041     
00042     public:
00043       
00049       virtual void velocityCallback(const geometry_msgs::Twist& msg) = 0;
00050       
00055       virtual void stop(void) = 0;
00056       
00062       virtual void calculateMotion(const ros::TimerEvent& event) = 0;
00063       
00068       inline geometry_msgs::Pose2D getPose(void)
00069       {
00070         return _pose;
00071       }
00072       
00078       inline void setPose(geometry_msgs::Pose2D new_pose)
00079       {
00080         _pose.x = new_pose.x;
00081         _pose.y = new_pose.y;
00082         _pose.theta = new_pose.theta;
00083       }
00084       
00089       inline geometry_msgs::Twist getVelocity() {
00090         return _currentTwist;
00091       }
00092 
00097       virtual ~MotionController(void) 
00098       {
00099       }
00100     
00101     protected:
00102       
00110       MotionController(
00111         const geometry_msgs::Pose2D& pose, 
00112         tf::TransformBroadcaster& tf, 
00113         const std::string& name)
00114           : _tfBroadcaster(tf), 
00115             _freq(0.1), 
00116             _namespace(name),
00117             _pose(pose) 
00118         { }
00119 
00120     protected:
00121       
00123       const std::string& _namespace;
00125       ros::Subscriber _velocitySubscrider;
00127       ros::Duration _freq;
00129       ros::Timer _calcTimer;
00131       tf::TransformBroadcaster& _tfBroadcaster;
00133       geometry_msgs::Pose2D _pose;
00135       geometry_msgs::Twist _currentTwist;
00136   };
00137     
00138   typedef boost::shared_ptr<MotionController> MotionControllerPtr;
00139     
00140 }
00141 
00142 
00143 #endif


stdr_robot
Author(s): Manos Tsardoulias, Chris Zalidis, Aris Thallas
autogenerated on Wed Sep 2 2015 03:36:25