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
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include <ros/ros.h>
00037 #include <boost/thread.hpp>
00038 #include <trajectory_msgs/JointTrajectory.h>
00039 #include <neo_PlatformCtrl/Kinematics.h>
00040 #include <neo_PlatformCtrl/MecanumKinematics.h>
00041 #include <tf/transform_broadcaster.h>
00042
00043 class PlatformCtrlNode
00044 {
00045 public:
00046 PlatformCtrlNode();
00047 virtual ~PlatformCtrlNode();
00048 ros::NodeHandle n;
00049 ros::Publisher topicPub_Odometry;
00050 ros::Subscriber topicSub_DriveState;
00051 ros::Publisher topicPub_DriveCommands;
00052 ros::Subscriber topicSub_ComVel;
00053 tf::TransformBroadcaster odom_broadcaster;
00054
00055 int init();
00056 void receiveCmd(const geometry_msgs::Twist& twist);
00057 void receiveOdo(const sensor_msgs::JointState& js);
00058 private:
00059 boost::mutex mutex;
00060 OdomPose p;
00061 Kinematics* kin;
00062 bool sendTransform;
00063 };
00064
00065 PlatformCtrlNode::PlatformCtrlNode()
00066 {
00067 kin = NULL;
00068 }
00069
00070 PlatformCtrlNode::~PlatformCtrlNode()
00071 {
00072 if( kin != NULL ) delete kin;
00073 }
00074
00075
00076 int PlatformCtrlNode::init()
00077 {
00078 std::string kinType;
00079 n.param<bool>("sendTransform",sendTransform,false);
00080 if(sendTransform)
00081 {
00082 ROS_INFO("platform ctrl node: sending transformation");
00083 } else {
00084
00085 ROS_INFO("platform ctrl node: sending no transformation");
00086 }
00087 n.getParam("kinematics", kinType);
00088
00089 if (kinType == "Mecanum4W")
00090 {
00091 double wheelDiameter, axisLength, axisWidth;
00092 Mecanum4WKinematics* mecKin = new Mecanum4WKinematics;
00093 kin = mecKin;
00094 if(n.hasParam("wheelDiameter"))
00095 {
00096 n.getParam("wheelDiameter",wheelDiameter);
00097 mecKin->setWheelDiameter(wheelDiameter);
00098 }
00099 else mecKin->setWheelDiameter(0.3);
00100 if(n.hasParam("robotWidth"))
00101 {
00102 n.getParam("robotWidth",axisWidth);
00103 mecKin->setAxis1Length(axisWidth);
00104 }
00105 else mecKin->setAxis1Length(0.5);
00106 if(n.hasParam("robotLength"))
00107 {
00108 n.getParam("robotLength",axisLength);
00109 mecKin->setAxis2Length(axisLength);
00110 }
00111 else mecKin->setAxis2Length(0.5);
00112 }
00113 else
00114 {
00115 ROS_ERROR("neo_PlatformCtrl-Error: unknown kinematic model");
00116
00117 }
00118 if(kin == NULL) return 1;
00119 p.xAbs = 0; p.yAbs = 0; p.phiAbs = 0;
00120 topicPub_Odometry = n.advertise<nav_msgs::Odometry>("/odom",1);
00121 topicSub_DriveState = n.subscribe("/Drives/JointStates",1,&PlatformCtrlNode::receiveOdo, this);
00122 topicPub_DriveCommands = n.advertise<trajectory_msgs::JointTrajectory>("/Drives/Set_Velocities",1);
00123 topicSub_ComVel = n.subscribe("/cmd_vel",1,&PlatformCtrlNode::receiveCmd, this);
00124 return 0;
00125 }
00126
00127
00128
00129 void PlatformCtrlNode::receiveCmd(const geometry_msgs::Twist& twist)
00130 {
00131 mutex.lock();
00132 trajectory_msgs::JointTrajectory traj;
00133 kin->execInvKin(twist,traj);
00134 topicPub_DriveCommands.publish(traj);
00135 mutex.unlock();
00136 }
00137
00138 void PlatformCtrlNode::receiveOdo(const sensor_msgs::JointState& js)
00139 {
00140 mutex.lock();
00141
00142 nav_msgs::Odometry odom;
00143 odom.header.stamp = ros::Time::now();
00144 odom.header.frame_id = "odom";
00145 odom.child_frame_id = "base_link";
00146 kin->execForwKin(js, odom, p);
00147 topicPub_Odometry.publish(odom);
00148
00149 if(sendTransform)
00150 {
00151 geometry_msgs::TransformStamped odom_trans;
00152 odom_trans.header.stamp = odom.header.stamp;
00153 odom_trans.header.frame_id = odom.header.frame_id;
00154 odom_trans.child_frame_id = odom.child_frame_id;
00155 odom_trans.transform.translation.x = odom.pose.pose.position.x;
00156 odom_trans.transform.translation.y = odom.pose.pose.position.y;
00157 odom_trans.transform.translation.z = odom.pose.pose.position.z;
00158 odom_trans.transform.rotation = odom.pose.pose.orientation;
00159 odom_broadcaster.sendTransform(odom_trans);
00160 }
00161 mutex.unlock();
00162 }
00163
00164
00165 int main (int argc, char** argv)
00166 {
00167 ros::init(argc, argv, "mecanum_node");
00168 PlatformCtrlNode node;
00169 if(node.init() != 0) ROS_ERROR("can't initialize neo_platformctrl_node");
00170 ros::spin();
00171 return 0;
00172 }
00173