$search
#include <ROSComm.hh>
| Public Member Functions | |
| bool | configure (FRIThread *fri) | 
| void | finish () | 
| bool | open () | 
| void | publishData (const RobotData &data, const RobotCommand &cmd) | 
| void | publishStatus (const RobotStatus &status) | 
| ROSComm () | |
| bool | runstop () | 
| void | start (FRIThread *fri) | 
| ~ROSComm () | |
| Private Member Functions | |
| void | impedanceCommand (const kuka_fri::ImpedanceCommand::ConstPtr &msg) | 
| void * | run () | 
| void | runstop_receiver (const std_msgs::BoolConstPtr &msg) | 
| void | status_update (diagnostic_updater::DiagnosticStatusWrapper &s) | 
| Static Private Member Functions | |
| static void * | run_s (void *ptr) | 
| Private Attributes | |
| diagnostic_updater::Updater * | diagnostic_ | 
| bool | exitRequested_ | 
| FRIThread * | fri_ | 
| sensor_msgs::JointState | joint_state_ | 
| ros::NodeHandle * | n_ | 
| ros::Publisher | pub_ | 
| double | rate_ | 
| bool | running_ | 
| std::string | side_ | 
| soft_runstop::Handler * | soft_runstop_handler_ | 
| RobotStatus | status_ | 
| ros::Subscriber | sub_ | 
| pthread_t | thread_ | 
Definition at line 15 of file ROSComm.hh.
| ROSComm::ROSComm | ( | ) | 
Definition at line 11 of file ROSComm.cc.
| ROSComm::~ROSComm | ( | ) | 
Definition at line 18 of file ROSComm.cc.
| bool ROSComm::configure | ( | FRIThread * | fri | ) | 
Definition at line 25 of file ROSComm.cc.
| void ROSComm::finish | ( | ) | 
Definition at line 244 of file ROSComm.cc.
| void ROSComm::impedanceCommand | ( | const kuka_fri::ImpedanceCommand::ConstPtr & | msg | ) |  [private] | 
Definition at line 165 of file ROSComm.cc.
| bool ROSComm::open | ( | ) | 
Definition at line 117 of file ROSComm.cc.
| void ROSComm::publishData | ( | const RobotData & | data, | |
| const RobotCommand & | cmd | |||
| ) | 
Definition at line 141 of file ROSComm.cc.
| void ROSComm::publishStatus | ( | const RobotStatus & | status | ) | 
Definition at line 158 of file ROSComm.cc.
| void * ROSComm::run | ( | void | ) |  [private] | 
Definition at line 202 of file ROSComm.cc.
| static void* ROSComm::run_s | ( | void * | ptr | ) |  [inline, static, private] | 
Definition at line 46 of file ROSComm.hh.
| bool ROSComm::runstop | ( | ) | 
Definition at line 189 of file ROSComm.cc.
| void ROSComm::runstop_receiver | ( | const std_msgs::BoolConstPtr & | msg | ) |  [private] | 
| void ROSComm::start | ( | FRIThread * | fri | ) | 
Definition at line 195 of file ROSComm.cc.
| void ROSComm::status_update | ( | diagnostic_updater::DiagnosticStatusWrapper & | s | ) |  [private] | 
Definition at line 73 of file ROSComm.cc.
| diagnostic_updater::Updater* ROSComm::diagnostic_  [private] | 
Definition at line 39 of file ROSComm.hh.
| bool ROSComm::exitRequested_  [private] | 
Definition at line 49 of file ROSComm.hh.
| FRIThread* ROSComm::fri_  [private] | 
Definition at line 43 of file ROSComm.hh.
| sensor_msgs::JointState ROSComm::joint_state_  [private] | 
Definition at line 40 of file ROSComm.hh.
| ros::NodeHandle* ROSComm::n_  [private] | 
Definition at line 35 of file ROSComm.hh.
| ros::Publisher ROSComm::pub_  [private] | 
Definition at line 36 of file ROSComm.hh.
| double ROSComm::rate_  [private] | 
Definition at line 44 of file ROSComm.hh.
| bool ROSComm::running_  [private] | 
Definition at line 49 of file ROSComm.hh.
| std::string ROSComm::side_  [private] | 
Definition at line 29 of file ROSComm.hh.
| soft_runstop::Handler* ROSComm::soft_runstop_handler_  [private] | 
Definition at line 30 of file ROSComm.hh.
| RobotStatus ROSComm::status_  [private] | 
Definition at line 31 of file ROSComm.hh.
| ros::Subscriber ROSComm::sub_  [private] | 
Definition at line 37 of file ROSComm.hh.
| pthread_t ROSComm::thread_  [private] | 
Definition at line 48 of file ROSComm.hh.