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/MecanumKinematics.h> 00037 #include <geometry_msgs/Vector3.h> 00038 00039 #define DIFF_PI 3.14159265 00040 00041 Mecanum4WKinematics::Mecanum4WKinematics() 00042 { 00043 m_dAxis1Length = 0.5; 00044 m_dAxis2Length = 0.7; 00045 } 00046 00047 void Mecanum4WKinematics::execForwKin(const sensor_msgs::JointState& js, nav_msgs::Odometry& odom, OdomPose& cpose) 00048 { 00049 current_time = ros::Time::now(); 00050 00051 /* See "Omnidirectional Mobile Robot -Design and Implementation": Ioan Doroftei, Victor Grosu and Veaceslav Spinu 00052 00053 l = l1 + l2 00054 00055 | | | w1 | 00056 | vx | | 1 1 1 1 | . | w2 | 00057 | vy | = R/4 | -1 1 1 -1 | | w3 | 00058 | wz | | -1/l 1/l -1/l 1/l | | w4 | 00059 */ 00060 //velocities: 00061 odom.twist.twist.linear.x = (js.velocity[0] + js.velocity[1] + js.velocity[2] + js.velocity[3]) * m_dDiam / 8; 00062 odom.twist.twist.linear.y = (js.velocity[1] - js.velocity[0] - js.velocity[3] + js.velocity[2]) * m_dDiam / 8; 00063 odom.twist.twist.linear.z = 0; 00064 odom.twist.twist.angular.x = 0; 00065 odom.twist.twist.angular.y = 0; 00066 odom.twist.twist.angular.z = (-js.velocity[0]+ js.velocity[1]-js.velocity[2]+js.velocity[3]) * m_dDiam / 4 / (m_dAxis1Length + m_dAxis2Length); 00067 //positions: 00068 double dt = (current_time - last_time).toSec(); 00069 cpose.xAbs += (odom.twist.twist.linear.x * cos(cpose.phiAbs) - odom.twist.twist.linear.y * sin(cpose.phiAbs)) * dt; 00070 cpose.yAbs += (odom.twist.twist.linear.x * sin(cpose.phiAbs) + odom.twist.twist.linear.y * cos(cpose.phiAbs)) * dt; 00071 cpose.phiAbs += odom.twist.twist.angular.z * dt; 00072 odom.pose.pose.position.x = cpose.xAbs; 00073 odom.pose.pose.position.y = cpose.yAbs; 00074 odom.pose.pose.position.z = 0; 00075 odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(cpose.phiAbs); 00076 last_time = current_time; 00077 } 00078 00079 void Mecanum4WKinematics::execInvKin(const geometry_msgs::Twist& twist, trajectory_msgs::JointTrajectory& traj) 00080 { 00081 //make sure that there's no old command in the message. 00082 traj.joint_names.clear(); 00083 traj.points.clear(); 00084 /* See "Omnidirectional Mobile Robot -Design and Implementation": Ioan Doroftei, Victor Grosu and Veaceslav Spinu 00085 00086 | w1 | | 1 -1 -(l1+l2) | 00087 | w2 | = 1/R | 1 1 (l1+l2) | . | vx | 00088 | w3 | | 1 1 -(l1+l2) | | vy | 00089 | w4 | | 1 -1 (l1+l2) | | wz | 00090 */ 00091 trajectory_msgs::JointTrajectoryPoint point; 00092 point.velocities.resize(4); 00093 // w1: 00094 traj.joint_names.push_back("wheel_front_left_base_link"); 00095 point.velocities[0] = 2 / m_dDiam * ( twist.linear.x - twist.linear.y - (m_dAxis1Length + m_dAxis2Length) / 2 * twist.angular.z); 00096 // w2: 00097 traj.joint_names.push_back("wheel_front_right_base_link"); 00098 point.velocities[1] = 2 / m_dDiam * ( twist.linear.x + twist.linear.y + (m_dAxis1Length + m_dAxis2Length) / 2 * twist.angular.z); 00099 // w3: 00100 traj.joint_names.push_back("wheel_back_left_base_link"); 00101 point.velocities[2] = 2 / m_dDiam * ( twist.linear.x + twist.linear.y - (m_dAxis1Length + m_dAxis2Length) / 2 * twist.angular.z); 00102 // w4: 00103 traj.joint_names.push_back("wheel_back_right_base_link"); 00104 point.velocities[3] = 2 / m_dDiam * ( twist.linear.x - twist.linear.y + (m_dAxis1Length + m_dAxis2Length) / 2 * twist.angular.z); 00105 traj.points.push_back(point); 00106 00107 } 00108 00109 00110 00111 void Mecanum4WKinematics::setAxis1Length(double dLength) 00112 { 00113 m_dAxis1Length = dLength; 00114 } 00115 00116 void Mecanum4WKinematics::setAxis2Length(double dLength) 00117 { 00118 m_dAxis2Length = dLength; 00119 } 00120 00121 00122 void Mecanum4WKinematics::setWheelDiameter(double dDiam) 00123 { 00124 m_dDiam = dDiam; 00125 }