Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface Class Reference

Message handler that relays robot service to the robot controller. More...

#include <fsrobo_r_robot_service_interface.h>

Public Member Functions

 FSRoboRRobotServiceInterface ()
 Default constructor. More...
 
virtual bool init (std::string default_ip="", int default_port=StandardSocketPorts::IO)
 Initialize robot connection using default method. More...
 
virtual bool init (SmplMsgConnection *connection)
 Initialize robot connection using specified method. More...
 
virtual void run ()
 Begin processing messages and publishing topics. More...
 
 ~FSRoboRRobotServiceInterface ()
 

Protected Member Functions

bool getPostureCB (fsrobo_r_msgs::GetPosture::Request &req, fsrobo_r_msgs::GetPosture::Response &res)
 Callback function registered to ROS get_posture service. Transform message into SimpleMessage objects and send commands to robot. More...
 
bool setIOCB (fsrobo_r_msgs::SetIO::Request &req, fsrobo_r_msgs::SetIO::Response &res)
 Callback function registered to ROS set_io service. Transform message into SimpleMessage objects and send commands to robot. More...
 
bool setPostureCB (fsrobo_r_msgs::SetPosture::Request &req, fsrobo_r_msgs::SetPosture::Response &res)
 Callback function registered to ROS set_posture service. Transform message into SimpleMessage objects and send commands to robot. More...
 
bool setToolOffsetCB (fsrobo_r_msgs::SetToolOffset::Request &req, fsrobo_r_msgs::SetToolOffset::Response &res)
 Callback function registered to ROS set_tool_offset service. Transform message into SimpleMessage objects and send commands to robot. More...
 

Protected Attributes

SmplMsgConnectionconnection_
 
TcpClient default_tcp_connection_
 
IOControl io_ctrl_
 
ros::NodeHandle node_
 
RobotConfigurator robot_configurator_
 
ros::ServiceServer srv_get_posture
 
ros::ServiceServer srv_set_io_
 
ros::ServiceServer srv_set_posture
 
ros::ServiceServer srv_set_tool_offset
 

Detailed Description

Message handler that relays robot service to the robot controller.

THIS CLASS IS NOT THREAD-SAFE

Definition at line 61 of file fsrobo_r_robot_service_interface.h.

Constructor & Destructor Documentation

fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::FSRoboRRobotServiceInterface ( )

Default constructor.

Definition at line 36 of file fsrobo_r_robot_service_interface.cpp.

fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::~FSRoboRRobotServiceInterface ( )

Definition at line 40 of file fsrobo_r_robot_service_interface.cpp.

Member Function Documentation

bool fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::getPostureCB ( fsrobo_r_msgs::GetPosture::Request &  req,
fsrobo_r_msgs::GetPosture::Response &  res 
)
protected

Callback function registered to ROS get_posture service. Transform message into SimpleMessage objects and send commands to robot.

Parameters
reqGetPosture request from service call
resGetPosture response to service call
Returns
true if success, false otherwise

Definition at line 138 of file fsrobo_r_robot_service_interface.cpp.

bool fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::init ( std::string  default_ip = "",
int  default_port = StandardSocketPorts::IO 
)
virtual

Initialize robot connection using default method.

Parameters
default_ipdefault IP address to use for robot connection [OPTIONAL]
  • this value will be used if ROS param "robot_ip_address" cannot be read
default_portdefault port to use for robot connection [OPTIONAL]
  • this value will be used if ROS param "~port" cannot be read
Returns
true on success, false otherwise

Definition at line 44 of file fsrobo_r_robot_service_interface.cpp.

bool fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::init ( SmplMsgConnection connection)
virtual

Initialize robot connection using specified method.

Parameters
connectionnew robot-connection instance (ALREADY INITIALIZED).
Returns
true on success, false otherwise

Definition at line 74 of file fsrobo_r_robot_service_interface.cpp.

virtual void fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::run ( )
inlinevirtual

Begin processing messages and publishing topics.

Definition at line 96 of file fsrobo_r_robot_service_interface.h.

bool fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::setIOCB ( fsrobo_r_msgs::SetIO::Request &  req,
fsrobo_r_msgs::SetIO::Response &  res 
)
protected

Callback function registered to ROS set_io service. Transform message into SimpleMessage objects and send commands to robot.

Parameters
reqSetIO request from service call
resSetIO response to service call
Returns
true if success, false otherwise

Definition at line 90 of file fsrobo_r_robot_service_interface.cpp.

bool fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::setPostureCB ( fsrobo_r_msgs::SetPosture::Request &  req,
fsrobo_r_msgs::SetPosture::Response &  res 
)
protected

Callback function registered to ROS set_posture service. Transform message into SimpleMessage objects and send commands to robot.

Parameters
reqSetPosture request from service call
resSetPosture response to service call
Returns
true if success, false otherwise

Definition at line 119 of file fsrobo_r_robot_service_interface.cpp.

bool fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::setToolOffsetCB ( fsrobo_r_msgs::SetToolOffset::Request &  req,
fsrobo_r_msgs::SetToolOffset::Response &  res 
)
protected

Callback function registered to ROS set_tool_offset service. Transform message into SimpleMessage objects and send commands to robot.

Parameters
reqSetToolOffset request from service call
resSetToolOffset response to service call
Returns
true if success, false otherwise

Definition at line 159 of file fsrobo_r_robot_service_interface.cpp.

Member Data Documentation

SmplMsgConnection* fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::connection_
protected

Definition at line 146 of file fsrobo_r_robot_service_interface.h.

TcpClient fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::default_tcp_connection_
protected

Definition at line 143 of file fsrobo_r_robot_service_interface.h.

IOControl fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::io_ctrl_
protected

Definition at line 104 of file fsrobo_r_robot_service_interface.h.

ros::NodeHandle fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::node_
protected

Definition at line 145 of file fsrobo_r_robot_service_interface.h.

RobotConfigurator fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::robot_configurator_
protected

Definition at line 105 of file fsrobo_r_robot_service_interface.h.

ros::ServiceServer fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::srv_get_posture
protected

Definition at line 101 of file fsrobo_r_robot_service_interface.h.

ros::ServiceServer fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::srv_set_io_
protected

Definition at line 99 of file fsrobo_r_robot_service_interface.h.

ros::ServiceServer fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::srv_set_posture
protected

Definition at line 100 of file fsrobo_r_robot_service_interface.h.

ros::ServiceServer fsrobo_r_driver::robot_service_interface::FSRoboRRobotServiceInterface::srv_set_tool_offset
protected

Definition at line 102 of file fsrobo_r_robot_service_interface.h.


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


fsrobo_r_driver
Author(s): F-ROSROBO
autogenerated on Sun Feb 9 2020 03:58:29