ideal_motion_controller.cpp
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  * Manos Tsardoulias, etsardou@gmail.com
18  * Aris Thallas, aris.thallas@gmail.com
19  * Chris Zalidis, zalidis@gmail.com
20 ******************************************************************************/
21 
23 
24 namespace stdr_robot {
25 
35  const geometry_msgs::Pose2D& pose,
37  ros::NodeHandle& n,
38  const std::string& name,
39  const stdr_msgs::KinematicMsg params)
40  : MotionController(pose, tf, name, n, params)
41  {
43  _freq,
45  this);
46  }
47 
54  {
56 
57  ros::Duration dt = ros::Time::now() - event.last_real;
58 
59  if (_currentTwist.angular.z == 0) {
60 
61  _pose.x += _currentTwist.linear.x * dt.toSec() * cosf(_pose.theta);
62  _pose.y += _currentTwist.linear.x * dt.toSec() * sinf(_pose.theta);
63  }
64  else {
65 
66  _pose.x += - _currentTwist.linear.x / _currentTwist.angular.z *
67  sinf(_pose.theta) +
68  _currentTwist.linear.x / _currentTwist.angular.z *
69  sinf(_pose.theta + dt.toSec() * _currentTwist.angular.z);
70 
71  _pose.y -= - _currentTwist.linear.x / _currentTwist.angular.z *
72  cosf(_pose.theta) +
73  _currentTwist.linear.x / _currentTwist.angular.z *
74  cosf(_pose.theta + dt.toSec() * _currentTwist.angular.z);
75  }
76  _pose.theta += _currentTwist.angular.z * dt.toSec();
77  }
78 
84  {
85 
86  }
87 
88 }
ros::Duration _freq
ROS timer for generating motion calculation events.
ros::Timer _calcTimer
Broadcaster of the robot tf transform.
The main namespace for STDR Robot.
Definition: exceptions.h:27
geometry_msgs::Pose2D _pose
Current motion command.
void calculateMotion(const ros::TimerEvent &event)
Calculates the motion - updates the robot pose.
~IdealMotionController(void)
Default destructor.
geometry_msgs::Twist _currentTwist
The kinematic model parameters.
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Abstract class that provides motion controller abstraction.
IdealMotionController(const geometry_msgs::Pose2D &pose, tf::TransformBroadcaster &tf, ros::NodeHandle &n, const std::string &name, const stdr_msgs::KinematicMsg params)
Default constructor.
static Time now()


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