R2RosTreeId.hpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <sensor_msgs/Imu.h>
00003 #include <sensor_msgs/JointState.h>
00004 
00005 #include "nasa_r2_common_msgs/WrenchState.h"
00006 #include "nasa_r2_common_msgs/StringArray.h"
00007 
00008 #include "nasa_robodyn_controllers_core/RosMsgTreeId.h"
00009 #include "nasa_robodyn_controllers_core/JointDynamicsData.h"
00010 #include "nasa_robodyn_controllers_core/KdlTreeId.h"
00011 #include "nasa_robodyn_utilities/RosMsgConverter.h"
00012 
00013 class R2RosTreeId
00014 {
00015 public:
00016     R2RosTreeId(std::string urdf, ros::NodeHandle &nh);
00017     virtual ~R2RosTreeId(){}
00018 
00019     void baseFrameCallback(const nasa_r2_common_msgs::StringArray &msg);
00020     void forceCallback(const nasa_r2_common_msgs::WrenchState &msg);
00021     void jointStateCallback(const sensor_msgs::JointState &msg);
00022     void trajCallback(const sensor_msgs::JointState &msg);
00023     void imuCallback(const sensor_msgs::Imu &msg);
00024 
00025     bool setGravity(double x, double y, double z, std::string frame, std::string mode);
00026 
00027 private:
00028     // Inv Dyn objects
00029     RosMsgTreeId rmt;
00030     KdlTreeId id;
00031     JointDynamicsData jd;
00032 
00033     // messages
00034     nasa_r2_common_msgs::StringArray baseMsg, completionMsg;
00035     nasa_r2_common_msgs::WrenchState forceMsg, emptyForceMsg, segForceMsg;
00036     sensor_msgs::JointState          actualStateMsg;
00037     sensor_msgs::JointState          trajStateMsg, emptyTrajMsg;
00038     sensor_msgs::JointState          jointTorqueMsg;
00039     sensor_msgs::JointState          jointInertiaMsg;
00040     sensor_msgs::Imu                 imuInMsg;
00041 
00042     //Publishers/Subscribers
00043 
00044     ros::Subscriber baseFrameIn;
00045     ros::Subscriber forceIn;
00046     ros::Subscriber jointStateIn;
00047     ros::Subscriber trajIn;
00048     ros::Subscriber imuIn;
00049 
00050     ros::Publisher torqueOut;
00051     ros::Publisher inertiaOut;
00052     ros::Publisher segForceOut;
00053     ros::Publisher completionOut;
00054 
00055     // properties
00056     std::vector<double> gravity;
00057     KDL::Vector gravity_kdl;
00058     std::string gravityFrame;
00059     KDL::Frame gravityXform;
00060     bool argos, useImu;
00061     std::string gravityBase, idMode;
00062     double yankLimBFF, loopRate;
00063 
00064     // variables for the id process
00065     std::string baseFrame, bfCmd;
00066     double bfFactor;
00067     KDL::Twist v_in, a_in, zeroTwist;
00068     KDL::Wrench f_out;
00069     KDL::RigidBodyInertia I_out;
00070     bool newBase;
00071 
00072 };


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