omni_motion_controller.h
Go to the documentation of this file.
1 /******************************************************************************
2  STDR Simulator - Simple Two DImensional Robot Simulator
3  Copyright (C) 2013 STDR Simulator
4  This program is free software; you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation; either version 3 of the License, or
7  (at your option) any later version.
8  This program is distributed in the hope that it will be useful,
9  but WITHOUT ANY WARRANTY; without even the implied warranty of
10  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
11  GNU General Public License for more details.
12  You should have received a copy of the GNU General Public License
13  along with this program; if not, write to the Free Software Foundation,
14  Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
15 
16 Authors:
17 
18 Oscar Lima Carrion, olima_84@yahoo.com
19 Ashok Meenakshi, mashoksc@gmail.com
20 Seguey Alexandrov, sergeyalexandrov@mail.com
21 
22 Review / Edits:
23 Manos Tsardoulias, etsardou@gmail.com
24 
25 About this code:
26 
27 This class represents a motion model for omnidirectional robot and could be
28 used to sample the possible pose given the starting pose and the commanded
29 robot's motion.
30 
31 The motion is decomposed into two translations alond the x axis of the
32 robot (forward), and along the y axis of the robot (lateral), and one
33 rotation.
34 ******************************************************************************/
35 
36 #ifndef OMNI_MOTION_CONTROLLER_H
37 #define OMNI_MOTION_CONTROLLER_H
38 
40 
45 namespace stdr_robot
46 {
47 
54  {
55 
56  public:
57 
67  const geometry_msgs::Pose2D& pose,
69  ros::NodeHandle& n,
70  const std::string& name,
71  const stdr_msgs::KinematicMsg params);
72 
78  void calculateMotion(const ros::TimerEvent& event);
79 
85  };
86 }
87 
88 
89 #endif
The main namespace for STDR Robot.
Definition: exceptions.h:27
A class that provides motion controller implementation. \ Inherits publicly MotionController.
void calculateMotion(const ros::TimerEvent &event)
Calculates the motion - updates the robot pose.
Abstract class that provides motion controller abstraction.
OmniMotionController(const geometry_msgs::Pose2D &pose, tf::TransformBroadcaster &tf, ros::NodeHandle &n, const std::string &name, const stdr_msgs::KinematicMsg params)
Default constructor.
~OmniMotionController(void)
Default destructor.


stdr_robot
Author(s): Manos Tsardoulias, Chris Zalidis, Aris Thallas
autogenerated on Mon Jun 10 2019 15:15:10