R2RosTreeId.cpp
Go to the documentation of this file.
00001 #include <r2_controllers_ros/R2RosTreeId.hpp>
00002 
00003 R2RosTreeId::R2RosTreeId(std::string urdf, ros::NodeHandle &nh):
00004     gravityFrame("/r2/robot_world"),
00005     argos(false),
00006     useImu(false),
00007     gravityBase("/r2/robot_world"),
00008     idMode("full"),
00009     yankLimBFF(0.1),
00010     loopRate(0.02),
00011     baseFrame("/r2/robot_world"),
00012     bfCmd("/r2/robot_world"),
00013     bfFactor(1.0),
00014     newBase(false)
00015 {
00016     id.loadFromFile(urdf);
00017     jd.InitializeMaps(id.getTree());
00018 
00019     torqueOut     = nh.advertise<sensor_msgs::JointState>("/joint_torque_commands", 1);
00020     inertiaOut    = nh.advertise<sensor_msgs::JointState>("/treeid_inertia", 1);
00021     segForceOut   = nh.advertise<nasa_r2_common_msgs::WrenchState>("/treeid_segment_forces", 1);
00022     completionOut = nh.advertise<nasa_r2_common_msgs::StringArray>("/completion", 1);
00023 
00024     baseFrameIn   = nh.subscribe("/base_frames", 1, &R2RosTreeId::baseFrameCallback, this);
00025     forceIn       = nh.subscribe("/treeid_external_forces", 1, &R2RosTreeId::forceCallback, this);
00026     jointStateIn  = nh.subscribe("/joint_states", 1, &R2RosTreeId::jointStateCallback, this);
00027     trajIn        = nh.subscribe("/joint_commands", 1, &R2RosTreeId::trajCallback, this);
00028     imuIn         = nh.subscribe("imu", 1, &R2RosTreeId::imuCallback, this);
00029 }
00030 
00031 bool R2RosTreeId::setGravity(double x, double y, double z, std::string frame, std::string mode)
00032 {
00033     if(!id.isBaseFrameInTree(frame))
00034     {
00035         ROS_ERROR("Unable to setGravity in R2RosTreeId, no such frame");
00036         return false;
00037     }
00038     idMode = mode;
00039     gravityFrame = frame;
00040     gravity.resize(3);
00041     gravity[0] = x;
00042     gravity[1] = y;
00043     gravity[2] = z;
00044     baseMsg.data.resize(1);
00045     baseMsg.data[0] = frame;
00046     rmt.setBaseFrame(baseMsg, frame);
00047     completionMsg.header.stamp = ros::Time::now();
00048     completionMsg.data.clear();
00049     completionMsg.data.push_back("base_frame");
00050     completionOut.publish(completionMsg);
00051     return true;
00052 }
00053 
00054 void R2RosTreeId::baseFrameCallback(const nasa_r2_common_msgs::StringArray &msg)
00055 {
00056     baseMsg = msg;
00057     if (rmt.setBaseFrame(baseMsg, bfCmd) > 0)
00058     {
00059         newBase = true;
00060         ROS_INFO("Received base frame");
00061     }
00062     else
00063     {
00064         ROS_ERROR("No base frames specified");
00065     }
00066 }
00067 
00068 void R2RosTreeId::forceCallback(const nasa_r2_common_msgs::WrenchState &msg)
00069 {
00070     forceMsg = msg;
00071 }
00072 
00073 void R2RosTreeId::trajCallback(const sensor_msgs::JointState &msg)
00074 {
00075     trajStateMsg = msg;
00076 }
00077 
00078 void R2RosTreeId::imuCallback(const sensor_msgs::Imu &msg)
00079 {
00080     imuInMsg = msg;
00081 }
00082 
00083 void R2RosTreeId::jointStateCallback(const sensor_msgs::JointState &msg)
00084 {
00085     if (idMode == nasa_r2_common_msgs::JointCommand::FULL || idMode == nasa_r2_common_msgs::JointCommand::INERTIA)
00086     {
00087         rmt.setJointData(msg, trajStateMsg, forceMsg, jd);
00088     }
00089     else
00090     {
00091         rmt.setJointData(msg, emptyTrajMsg, emptyForceMsg, jd);
00092     }
00093 
00094     if (idMode == nasa_r2_common_msgs::JointCommand::FULL || idMode == nasa_r2_common_msgs::JointCommand::GRAVITY)
00095     {
00096         // Blend base frame switching
00097         if (gravity[0] != 0 || gravity[1] != 0 || gravity[2] != 0)
00098         {
00099             if (baseFrame != bfCmd)
00100             {
00101                 bfFactor -= yankLimBFF*loopRate;
00102             }
00103 
00104             if (baseFrame == bfCmd && bfFactor < 1.0)
00105             {
00106                 bfFactor += yankLimBFF*loopRate;
00107             }
00108 
00109             if (bfFactor <= 0.0 )
00110             {
00111                 baseFrame = bfCmd;
00112                 bfFactor = 0.0;
00113             }
00114 
00115             if (bfFactor > 1.0)
00116             {
00117                 bfFactor = 1.0;
00118             }
00119         }
00120 
00121         // Find gravity vector and do dynamics
00122         gravity_kdl = bfFactor * KDL::Vector(-gravity[0], -gravity[1], -gravity[2]);
00123         id.getAccelInBaseFrame(gravity_kdl, gravityFrame, jd, baseFrame, a_in);
00124         // Gravity Comp
00125         id.treeRecursiveNewtonEuler(jd, baseFrame, "null", v_in, a_in, f_out, I_out);
00126     }
00127     else
00128     {
00129         // no gravity comp
00130         id.treeRecursiveNewtonEuler(jd, baseFrame, "null", zeroTwist, zeroTwist, f_out, I_out);
00131     }
00132 
00133     // Populate & send messages
00134     if (idMode != nasa_r2_common_msgs::JointCommand::NONE)
00135     {
00136         rmt.getJointCommand(jd, jointTorqueMsg);
00137     }
00138     else
00139     {
00140         rmt.setEmptyTorqueMsg(jd, jointTorqueMsg);
00141     }
00142 
00143     // Inertia and force happens regardless
00144     rmt.getJointInertias(jd, jointInertiaMsg);
00145     rmt.getSegmentForces(jd, segForceMsg);
00146 
00147     torqueOut.publish(jointTorqueMsg);
00148     inertiaOut.publish(jointInertiaMsg);
00149     segForceOut.publish(segForceMsg);
00150 
00151     if (bfFactor >= 1.0 && bfCmd == baseFrame && newBase)
00152     {
00153         completionMsg.header.stamp = ros::Time::now();
00154         completionOut.publish(completionMsg);
00155         newBase = false;
00156     }
00157 }
00158 


r2_controllers_ros
Author(s): Allison Thackston
autogenerated on Mon Oct 6 2014 02:46:50