00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2011, Neobotix GmbH 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Neobotix nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 00036 #include <neo_PlatformCtrl/DiffDrive2WKinematics.h> 00037 #include <geometry_msgs/Vector3.h> 00038 00039 #define DIFF_PI 3.14159265 00040 00041 DiffDrive2WKinematics::DiffDrive2WKinematics() 00042 { 00043 m_dAxisLength = 0; 00044 } 00045 00046 void DiffDrive2WKinematics::execForwKin(const sensor_msgs::JointState& js, nav_msgs::Odometry& odom, OdomPose& cpose) 00047 { 00048 current_time = ros::Time::now(); 00049 //velocities: 00050 odom.twist.twist.linear.x = 0.5 * (js.velocity[0] + js.velocity[1]) * m_dDiam * 0.5; 00051 odom.twist.twist.linear.y = 0; 00052 odom.twist.twist.linear.z = 0; 00053 odom.twist.twist.angular.x = 0; 00054 odom.twist.twist.angular.y = 0; 00055 odom.twist.twist.angular.z = (js.velocity[0] - js.velocity[1]) * m_dDiam /2 / m_dAxisLength; 00056 //positions: 00057 double dt = (current_time - last_time).toSec(); 00058 cpose.xAbs += odom.twist.twist.linear.x * dt * cos(cpose.phiAbs); 00059 cpose.yAbs += odom.twist.twist.linear.x *dt * sin(cpose.phiAbs); 00060 cpose.phiAbs += odom.twist.twist.angular.z * dt; 00061 odom.pose.pose.position.x = cpose.xAbs; 00062 odom.pose.pose.position.y = cpose.yAbs; 00063 odom.pose.pose.position.z = 0; 00064 odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(cpose.phiAbs); 00065 last_time = current_time; 00066 } 00067 00068 void DiffDrive2WKinematics::execInvKin(const geometry_msgs::Twist& twist, trajectory_msgs::JointTrajectory& traj) 00069 { 00070 traj.joint_names.clear(); 00071 traj.points.clear(); 00072 00073 //angular velocity in rad 00074 trajectory_msgs::JointTrajectoryPoint point; 00075 point.velocities.resize(4); 00076 // w1: 00077 traj.joint_names.push_back("wheel_front_left_base_link"); 00078 point.velocities[0] = (twist.linear.x + (twist.angular.z * m_dAxisLength) / 2) * 2 / m_dDiam; 00079 // w2: 00080 traj.joint_names.push_back("wheel_front_right_base_link"); 00081 point.velocities[1] = (twist.linear.x - (twist.angular.z * m_dAxisLength) / 2) * 2 / m_dDiam; 00082 traj.points.push_back(point); 00083 } 00084 00085 void DiffDrive2WKinematics::setAxisLength(double dLength) 00086 { 00087 m_dAxisLength = dLength; 00088 } 00089 00090 void DiffDrive2WKinematics::setWheelDiameter(double dDiam) 00091 { 00092 m_dDiam = dDiam; 00093 }