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
KDL::Jacobian jac_
std::vector< double > jnt_pos_
std::vector< double > jnt_pos_cmd_
std::vector< double > jnt_pos_old_
std::vector< double > jnt_trq_
std::vector< double > jnt_trq_cmd_
std::vector< double > 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< KDL::Jacobianport_Jacobian
RTT::InputPort
< lwr_fri::FriJointImpedance
port_JointImpedanceCommand
RTT::OutputPort< std::vector
< double > > 
port_JointPosition
RTT::InputPort< std::vector
< double > > 
port_JointPositionCommand
RTT::OutputPort< std::vector
< double > > 
port_JointTorque
RTT::InputPort< std::vector
< double > > 
port_JointTorqueCommand
RTT::OutputPort< std::vector
< double > > 
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 50 of file FRIComponent.cpp.


Constructor & Destructor Documentation

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

Definition at line 52 of file FRIComponent.cpp.

Definition at line 78 of file FRIComponent.cpp.


Member Function Documentation

Definition at line 81 of file FRIComponent.cpp.

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

Definition at line 120 of file FRIComponent.cpp.

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

Definition at line 429 of file FRIComponent.cpp.

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

Definition at line 405 of file FRIComponent.cpp.

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

Definition at line 416 of file FRIComponent.cpp.

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

Definition at line 427 of file FRIComponent.cpp.

Definition at line 101 of file FRIComponent.cpp.

void FRIComponent::stopHook ( ) [inline]

Definition at line 107 of file FRIComponent.cpp.

void FRIComponent::updateHook ( ) [inline]

Definition at line 112 of file FRIComponent.cpp.


Member Data Documentation

uint16_t FRIComponent::counter [private]

Definition at line 398 of file FRIComponent.cpp.

uint16_t FRIComponent::fri_state_last [private]

Definition at line 398 of file FRIComponent.cpp.

Definition at line 392 of file FRIComponent.cpp.

Definition at line 384 of file FRIComponent.cpp.

Definition at line 389 of file FRIComponent.cpp.

Definition at line 385 of file FRIComponent.cpp.

Definition at line 386 of file FRIComponent.cpp.

Definition at line 390 of file FRIComponent.cpp.

Definition at line 387 of file FRIComponent.cpp.

std::string FRIComponent::joint_names_prefix [private]

Definition at line 397 of file FRIComponent.cpp.

tFriCmdData FRIComponent::m_cmd_data [private]

Definition at line 403 of file FRIComponent.cpp.

Definition at line 396 of file FRIComponent.cpp.

tFriMsrData FRIComponent::m_msr_data [private]

Definition at line 402 of file FRIComponent.cpp.

struct sockaddr_in FRIComponent::m_remote_addr [private]

Definition at line 399 of file FRIComponent.cpp.

Definition at line 396 of file FRIComponent.cpp.

socklen_t FRIComponent::m_sock_addr_len [private]

Definition at line 400 of file FRIComponent.cpp.

int FRIComponent::m_socket [private]

Definition at line 396 of file FRIComponent.cpp.

Definition at line 361 of file FRIComponent.cpp.

Definition at line 374 of file FRIComponent.cpp.

Definition at line 363 of file FRIComponent.cpp.

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

Definition at line 373 of file FRIComponent.cpp.

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

Definition at line 369 of file FRIComponent.cpp.

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

Definition at line 362 of file FRIComponent.cpp.

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

Definition at line 371 of file FRIComponent.cpp.

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

Definition at line 376 of file FRIComponent.cpp.

Definition at line 364 of file FRIComponent.cpp.

RTT::OutputPort<std::vector<double> > FRIComponent::port_JointPosition [private]

Definition at line 378 of file FRIComponent.cpp.

RTT::InputPort<std::vector<double> > FRIComponent::port_JointPositionCommand [private]

Definition at line 365 of file FRIComponent.cpp.

RTT::OutputPort<std::vector<double> > FRIComponent::port_JointTorque [private]

Definition at line 377 of file FRIComponent.cpp.

RTT::InputPort<std::vector<double> > FRIComponent::port_JointTorqueCommand [private]

Definition at line 366 of file FRIComponent.cpp.

RTT::OutputPort<std::vector<double> > FRIComponent::port_JointVelocity [private]

Definition at line 372 of file FRIComponent.cpp.

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

Definition at line 367 of file FRIComponent.cpp.

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

Definition at line 375 of file FRIComponent.cpp.

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

Definition at line 370 of file FRIComponent.cpp.

Definition at line 380 of file FRIComponent.cpp.

Definition at line 394 of file FRIComponent.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


lwr_fri
Author(s): Ruben Smits
autogenerated on Thu Nov 14 2013 11:55:34