Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 #include <stdr_robot/motion/ideal_motion_controller.h>
00023
00024 namespace stdr_robot {
00025
00034 IdealMotionController::IdealMotionController(
00035 const geometry_msgs::Pose2D& pose,
00036 tf::TransformBroadcaster& tf,
00037 ros::NodeHandle& n,
00038 const std::string& name,
00039 const stdr_msgs::KinematicMsg params)
00040 : MotionController(pose, tf, name, n, params)
00041 {
00042 _calcTimer = n.createTimer(
00043 _freq,
00044 &IdealMotionController::calculateMotion,
00045 this);
00046 }
00047
00053 void IdealMotionController::calculateMotion(const ros::TimerEvent& event)
00054 {
00056
00057 ros::Duration dt = ros::Time::now() - event.last_real;
00058
00059 if (_currentTwist.angular.z == 0) {
00060
00061 _pose.x += _currentTwist.linear.x * dt.toSec() * cosf(_pose.theta);
00062 _pose.y += _currentTwist.linear.x * dt.toSec() * sinf(_pose.theta);
00063 }
00064 else {
00065
00066 _pose.x += - _currentTwist.linear.x / _currentTwist.angular.z *
00067 sinf(_pose.theta) +
00068 _currentTwist.linear.x / _currentTwist.angular.z *
00069 sinf(_pose.theta + dt.toSec() * _currentTwist.angular.z);
00070
00071 _pose.y -= - _currentTwist.linear.x / _currentTwist.angular.z *
00072 cosf(_pose.theta) +
00073 _currentTwist.linear.x / _currentTwist.angular.z *
00074 cosf(_pose.theta + dt.toSec() * _currentTwist.angular.z);
00075 }
00076 _pose.theta += _currentTwist.angular.z * dt.toSec();
00077 }
00078
00083 IdealMotionController::~IdealMotionController(void)
00084 {
00085
00086 }
00087
00088 }