Public Member Functions | Private Attributes
R2RosTreeId Class Reference

#include <R2RosTreeId.hpp>

List of all members.

Public Member Functions

void baseFrameCallback (const nasa_r2_common_msgs::StringArray &msg)
void forceCallback (const nasa_r2_common_msgs::WrenchState &msg)
void imuCallback (const sensor_msgs::Imu &msg)
void jointStateCallback (const sensor_msgs::JointState &msg)
 R2RosTreeId (std::string urdf, ros::NodeHandle &nh)
bool setGravity (double x, double y, double z, std::string frame, std::string mode)
void trajCallback (const sensor_msgs::JointState &msg)
virtual ~R2RosTreeId ()

Private Attributes

KDL::Twist a_in
sensor_msgs::JointState actualStateMsg
bool argos
std::string baseFrame
ros::Subscriber baseFrameIn
nasa_r2_common_msgs::StringArray baseMsg
std::string bfCmd
double bfFactor
nasa_r2_common_msgs::StringArray completionMsg
ros::Publisher completionOut
nasa_r2_common_msgs::WrenchState emptyForceMsg
sensor_msgs::JointState emptyTrajMsg
KDL::Wrench f_out
ros::Subscriber forceIn
nasa_r2_common_msgs::WrenchState forceMsg
std::vector< double > gravity
KDL::Vector gravity_kdl
std::string gravityBase
std::string gravityFrame
KDL::Frame gravityXform
KDL::RigidBodyInertia I_out
KdlTreeId id
std::string idMode
ros::Subscriber imuIn
sensor_msgs::Imu imuInMsg
ros::Publisher inertiaOut
JointDynamicsData jd
sensor_msgs::JointState jointInertiaMsg
ros::Subscriber jointStateIn
sensor_msgs::JointState jointTorqueMsg
double loopRate
bool newBase
RosMsgTreeId rmt
nasa_r2_common_msgs::WrenchState segForceMsg
ros::Publisher segForceOut
ros::Publisher torqueOut
ros::Subscriber trajIn
sensor_msgs::JointState trajStateMsg
bool useImu
KDL::Twist v_in
double yankLimBFF
KDL::Twist zeroTwist

Detailed Description

Definition at line 13 of file R2RosTreeId.hpp.


Constructor & Destructor Documentation

R2RosTreeId::R2RosTreeId ( std::string  urdf,
ros::NodeHandle nh 
)

Definition at line 3 of file R2RosTreeId.cpp.

virtual R2RosTreeId::~R2RosTreeId ( ) [inline, virtual]

Definition at line 17 of file R2RosTreeId.hpp.


Member Function Documentation

Definition at line 54 of file R2RosTreeId.cpp.

Definition at line 68 of file R2RosTreeId.cpp.

void R2RosTreeId::imuCallback ( const sensor_msgs::Imu &  msg)

Definition at line 78 of file R2RosTreeId.cpp.

void R2RosTreeId::jointStateCallback ( const sensor_msgs::JointState &  msg)

Definition at line 83 of file R2RosTreeId.cpp.

bool R2RosTreeId::setGravity ( double  x,
double  y,
double  z,
std::string  frame,
std::string  mode 
)

Definition at line 31 of file R2RosTreeId.cpp.

void R2RosTreeId::trajCallback ( const sensor_msgs::JointState &  msg)

Definition at line 73 of file R2RosTreeId.cpp.


Member Data Documentation

Definition at line 67 of file R2RosTreeId.hpp.

sensor_msgs::JointState R2RosTreeId::actualStateMsg [private]

Definition at line 36 of file R2RosTreeId.hpp.

bool R2RosTreeId::argos [private]

Definition at line 60 of file R2RosTreeId.hpp.

std::string R2RosTreeId::baseFrame [private]

Definition at line 65 of file R2RosTreeId.hpp.

Definition at line 44 of file R2RosTreeId.hpp.

Definition at line 34 of file R2RosTreeId.hpp.

std::string R2RosTreeId::bfCmd [private]

Definition at line 65 of file R2RosTreeId.hpp.

double R2RosTreeId::bfFactor [private]

Definition at line 66 of file R2RosTreeId.hpp.

Definition at line 34 of file R2RosTreeId.hpp.

Definition at line 53 of file R2RosTreeId.hpp.

Definition at line 35 of file R2RosTreeId.hpp.

sensor_msgs::JointState R2RosTreeId::emptyTrajMsg [private]

Definition at line 37 of file R2RosTreeId.hpp.

Definition at line 68 of file R2RosTreeId.hpp.

Definition at line 45 of file R2RosTreeId.hpp.

Definition at line 35 of file R2RosTreeId.hpp.

std::vector<double> R2RosTreeId::gravity [private]

Definition at line 56 of file R2RosTreeId.hpp.

Definition at line 57 of file R2RosTreeId.hpp.

std::string R2RosTreeId::gravityBase [private]

Definition at line 61 of file R2RosTreeId.hpp.

std::string R2RosTreeId::gravityFrame [private]

Definition at line 58 of file R2RosTreeId.hpp.

Definition at line 59 of file R2RosTreeId.hpp.

Definition at line 69 of file R2RosTreeId.hpp.

KdlTreeId R2RosTreeId::id [private]

Definition at line 30 of file R2RosTreeId.hpp.

std::string R2RosTreeId::idMode [private]

Definition at line 61 of file R2RosTreeId.hpp.

Definition at line 48 of file R2RosTreeId.hpp.

sensor_msgs::Imu R2RosTreeId::imuInMsg [private]

Definition at line 40 of file R2RosTreeId.hpp.

Definition at line 51 of file R2RosTreeId.hpp.

JointDynamicsData R2RosTreeId::jd [private]

Definition at line 31 of file R2RosTreeId.hpp.

sensor_msgs::JointState R2RosTreeId::jointInertiaMsg [private]

Definition at line 39 of file R2RosTreeId.hpp.

Definition at line 46 of file R2RosTreeId.hpp.

sensor_msgs::JointState R2RosTreeId::jointTorqueMsg [private]

Definition at line 38 of file R2RosTreeId.hpp.

double R2RosTreeId::loopRate [private]

Definition at line 62 of file R2RosTreeId.hpp.

bool R2RosTreeId::newBase [private]

Definition at line 70 of file R2RosTreeId.hpp.

RosMsgTreeId R2RosTreeId::rmt [private]

Definition at line 29 of file R2RosTreeId.hpp.

Definition at line 35 of file R2RosTreeId.hpp.

Definition at line 52 of file R2RosTreeId.hpp.

Definition at line 50 of file R2RosTreeId.hpp.

Definition at line 47 of file R2RosTreeId.hpp.

sensor_msgs::JointState R2RosTreeId::trajStateMsg [private]

Definition at line 37 of file R2RosTreeId.hpp.

bool R2RosTreeId::useImu [private]

Definition at line 60 of file R2RosTreeId.hpp.

Definition at line 67 of file R2RosTreeId.hpp.

double R2RosTreeId::yankLimBFF [private]

Definition at line 62 of file R2RosTreeId.hpp.

Definition at line 67 of file R2RosTreeId.hpp.


The documentation for this class was generated from the following files:


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