Public Member Functions | Private Member Functions | Private Attributes
FRIComponent Class Reference

List of all members.

Public Member Functions

bool configureHook ()
 FRIComponent (const std::string &name)
bool startHook ()
void stopHook ()
void updateHook ()
 ~FRIComponent ()

Private Member Functions

void doComm ()
int fri_create_socket ()
int fri_recv ()
int fri_send ()
bool isPowerOn ()

Private Attributes

uint16_t counter
uint16_t fri_state_last
Eigen::VectorXd grav_trq_
KDL::Jacobian jac_
Eigen::VectorXd jnt_pos_
Eigen::VectorXd jnt_pos_cmd_
Eigen::VectorXd jnt_pos_old_
Eigen::VectorXd jnt_trq_
Eigen::VectorXd jnt_trq_cmd_
Eigen::VectorXd jnt_vel_
std::string joint_names_prefix
tFriCmdData m_cmd_data
int m_control_mode
tFriMsrData m_msr_data
struct sockaddr_in m_remote_addr
int m_remote_port
socklen_t m_sock_addr_len
int m_socket
RTT::InputPort
< lwr_fri::CartesianImpedance > 
port_CartesianImpedanceCommand
RTT::OutputPort
< geometry_msgs::Pose > 
port_CartesianPosition
RTT::InputPort
< geometry_msgs::Pose > 
port_CartesianPositionCommand
RTT::OutputPort
< geometry_msgs::Twist > 
port_CartesianVelocity
RTT::OutputPort
< geometry_msgs::Wrench > 
port_CartesianWrench
RTT::InputPort
< geometry_msgs::Wrench > 
port_CartesianWrenchCommand
RTT::OutputPort< tFriIntfState > port_FRIState
RTT::OutputPort< Eigen::VectorXd > port_GravityTorque
RTT::OutputPort< KDL::Jacobianport_Jacobian
RTT::InputPort
< lwr_fri::FriJointImpedance > 
port_JointImpedanceCommand
RTT::OutputPort< Eigen::VectorXd > port_JointPosition
RTT::InputPort< Eigen::VectorXd > port_JointPositionCommand
RTT::OutputPort< Eigen::VectorXd > port_JointTorque
RTT::InputPort< Eigen::VectorXd > port_JointTorqueCommand
RTT::OutputPort< Eigen::VectorXd > port_JointVelocity
RTT::InputPort< std_msgs::Int32 > port_KRL_CMD
RTT::OutputPort< Matrix77dport_MassMatrix
RTT::OutputPort< tFriRobotState > port_RobotState
int prop_fri_port
KDL::Frame T_old

Detailed Description

Definition at line 49 of file FRIComponent.cpp.


Constructor & Destructor Documentation

FRIComponent::FRIComponent ( const std::string &  name) [inline]

Definition at line 51 of file FRIComponent.cpp.

Definition at line 78 of file FRIComponent.cpp.


Member Function Documentation

bool FRIComponent::configureHook ( ) [inline]

Definition at line 81 of file FRIComponent.cpp.

void FRIComponent::doComm ( ) [inline, private]

Definition at line 123 of file FRIComponent.cpp.

int FRIComponent::fri_create_socket ( ) [inline, private]

Definition at line 436 of file FRIComponent.cpp.

int FRIComponent::fri_recv ( ) [inline, private]

Definition at line 412 of file FRIComponent.cpp.

int FRIComponent::fri_send ( ) [inline, private]

Definition at line 423 of file FRIComponent.cpp.

bool FRIComponent::isPowerOn ( ) [inline, private]

Definition at line 434 of file FRIComponent.cpp.

bool FRIComponent::startHook ( ) [inline]

Definition at line 104 of file FRIComponent.cpp.

void FRIComponent::stopHook ( ) [inline]

Definition at line 110 of file FRIComponent.cpp.

void FRIComponent::updateHook ( ) [inline]

Definition at line 115 of file FRIComponent.cpp.


Member Data Documentation

uint16_t FRIComponent::counter [private]

Definition at line 405 of file FRIComponent.cpp.

uint16_t FRIComponent::fri_state_last [private]

Definition at line 405 of file FRIComponent.cpp.

Eigen::VectorXd FRIComponent::grav_trq_ [private]

Definition at line 393 of file FRIComponent.cpp.

Definition at line 399 of file FRIComponent.cpp.

Eigen::VectorXd FRIComponent::jnt_pos_ [private]

Definition at line 390 of file FRIComponent.cpp.

Eigen::VectorXd FRIComponent::jnt_pos_cmd_ [private]

Definition at line 396 of file FRIComponent.cpp.

Eigen::VectorXd FRIComponent::jnt_pos_old_ [private]

Definition at line 391 of file FRIComponent.cpp.

Eigen::VectorXd FRIComponent::jnt_trq_ [private]

Definition at line 392 of file FRIComponent.cpp.

Eigen::VectorXd FRIComponent::jnt_trq_cmd_ [private]

Definition at line 397 of file FRIComponent.cpp.

Eigen::VectorXd FRIComponent::jnt_vel_ [private]

Definition at line 394 of file FRIComponent.cpp.

std::string FRIComponent::joint_names_prefix [private]

Definition at line 404 of file FRIComponent.cpp.

tFriCmdData FRIComponent::m_cmd_data [private]

Definition at line 410 of file FRIComponent.cpp.

Definition at line 403 of file FRIComponent.cpp.

tFriMsrData FRIComponent::m_msr_data [private]

Definition at line 409 of file FRIComponent.cpp.

struct sockaddr_in FRIComponent::m_remote_addr [private]

Definition at line 406 of file FRIComponent.cpp.

Definition at line 403 of file FRIComponent.cpp.

socklen_t FRIComponent::m_sock_addr_len [private]

Definition at line 407 of file FRIComponent.cpp.

int FRIComponent::m_socket [private]

Definition at line 403 of file FRIComponent.cpp.

RTT::InputPort<lwr_fri::CartesianImpedance > FRIComponent::port_CartesianImpedanceCommand [private]

Definition at line 366 of file FRIComponent.cpp.

RTT::OutputPort<geometry_msgs::Pose > FRIComponent::port_CartesianPosition [private]

Definition at line 379 of file FRIComponent.cpp.

RTT::InputPort<geometry_msgs::Pose > FRIComponent::port_CartesianPositionCommand [private]

Definition at line 368 of file FRIComponent.cpp.

RTT::OutputPort<geometry_msgs::Twist > FRIComponent::port_CartesianVelocity [private]

Definition at line 378 of file FRIComponent.cpp.

RTT::OutputPort<geometry_msgs::Wrench > FRIComponent::port_CartesianWrench [private]

Definition at line 374 of file FRIComponent.cpp.

RTT::InputPort<geometry_msgs::Wrench > FRIComponent::port_CartesianWrenchCommand [private]

Definition at line 367 of file FRIComponent.cpp.

RTT::OutputPort<tFriIntfState > FRIComponent::port_FRIState [private]

Definition at line 376 of file FRIComponent.cpp.

RTT::OutputPort<Eigen::VectorXd > FRIComponent::port_GravityTorque [private]

Definition at line 383 of file FRIComponent.cpp.

RTT::OutputPort<KDL::Jacobian > FRIComponent::port_Jacobian [private]

Definition at line 381 of file FRIComponent.cpp.

RTT::InputPort<lwr_fri::FriJointImpedance > FRIComponent::port_JointImpedanceCommand [private]

Definition at line 369 of file FRIComponent.cpp.

RTT::OutputPort<Eigen::VectorXd > FRIComponent::port_JointPosition [private]

Definition at line 384 of file FRIComponent.cpp.

RTT::InputPort<Eigen::VectorXd > FRIComponent::port_JointPositionCommand [private]

Definition at line 370 of file FRIComponent.cpp.

RTT::OutputPort<Eigen::VectorXd > FRIComponent::port_JointTorque [private]

Definition at line 382 of file FRIComponent.cpp.

RTT::InputPort<Eigen::VectorXd > FRIComponent::port_JointTorqueCommand [private]

Definition at line 371 of file FRIComponent.cpp.

RTT::OutputPort<Eigen::VectorXd > FRIComponent::port_JointVelocity [private]

Definition at line 377 of file FRIComponent.cpp.

RTT::InputPort<std_msgs::Int32 > FRIComponent::port_KRL_CMD [private]

Definition at line 372 of file FRIComponent.cpp.

RTT::OutputPort<Matrix77d > FRIComponent::port_MassMatrix [private]

Definition at line 380 of file FRIComponent.cpp.

RTT::OutputPort<tFriRobotState > FRIComponent::port_RobotState [private]

Definition at line 375 of file FRIComponent.cpp.

Definition at line 386 of file FRIComponent.cpp.

Definition at line 401 of file FRIComponent.cpp.


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


lwr_fri
Author(s): Konrad Banachowicz
autogenerated on Mon Oct 6 2014 01:58:05