Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
motoman::io_relay::MotomanIORelay Class Reference

Message handler that sends I/O service requests to the robot controller and receives the responses. More...

#include <io_relay.h>

Public Member Functions

bool init (int default_port)
 Class initializer. More...
 

Protected Member Functions

bool readSingleIoCB (motoman_msgs::ReadSingleIO::Request &req, motoman_msgs::ReadSingleIO::Response &res)
 
bool writeSingleIoCB (motoman_msgs::WriteSingleIO::Request &req, motoman_msgs::WriteSingleIO::Response &res)
 

Protected Attributes

TcpClient default_tcp_connection_
 
io_ctrl::MotomanIoCtrl io_ctrl_
 
boost::mutex mutex_
 
ros::NodeHandle node_
 
ros::ServiceServer srv_read_single_io
 
ros::ServiceServer srv_write_single_io
 

Detailed Description

Message handler that sends I/O service requests to the robot controller and receives the responses.

Definition at line 51 of file io_relay.h.

Member Function Documentation

bool motoman::io_relay::MotomanIORelay::init ( int  default_port)

Class initializer.

Parameters
default_port
Returns
true on success, false otherwise

Definition at line 47 of file io_relay.cpp.

bool motoman::io_relay::MotomanIORelay::readSingleIoCB ( motoman_msgs::ReadSingleIO::Request &  req,
motoman_msgs::ReadSingleIO::Response &  res 
)
protected

Definition at line 105 of file io_relay.cpp.

bool motoman::io_relay::MotomanIORelay::writeSingleIoCB ( motoman_msgs::WriteSingleIO::Request &  req,
motoman_msgs::WriteSingleIO::Response &  res 
)
protected

Definition at line 141 of file io_relay.cpp.

Member Data Documentation

TcpClient motoman::io_relay::MotomanIORelay::default_tcp_connection_
protected

Definition at line 70 of file io_relay.h.

io_ctrl::MotomanIoCtrl motoman::io_relay::MotomanIORelay::io_ctrl_
protected

Definition at line 63 of file io_relay.h.

boost::mutex motoman::io_relay::MotomanIORelay::mutex_
protected

Definition at line 69 of file io_relay.h.

ros::NodeHandle motoman::io_relay::MotomanIORelay::node_
protected

Definition at line 68 of file io_relay.h.

ros::ServiceServer motoman::io_relay::MotomanIORelay::srv_read_single_io
protected

Definition at line 65 of file io_relay.h.

ros::ServiceServer motoman::io_relay::MotomanIORelay::srv_write_single_io
protected

Definition at line 66 of file io_relay.h.


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


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute), Ted Miller (MotoROS) (Yaskawa Motoman), Eric Marcil (MotoROS) (Yaskawa Motoman)
autogenerated on Sat May 8 2021 02:27:44