#include <dsr_hw_interface.h>
Classes | |
struct | Joint |
Public Member Functions | |
DRHWInterface (ros::NodeHandle &nh) | |
bool | init () |
int | MsgPublisher_RobotState () |
virtual void | read (ros::Duration &elapsed_time) |
virtual void | write (ros::Duration &elapsed_time) |
virtual | ~DRHWInterface () |
Public Member Functions inherited from hardware_interface::RobotHW | |
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
virtual bool | checkForConflict (const std::list< ControllerInfo > &info) const |
virtual void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
virtual void | doSwitch (const std::list< ControllerInfo > &, const std::list< ControllerInfo > &) |
virtual bool | init (ros::NodeHandle &root_nh, ros::NodeHandle &robot_hw_nh) |
virtual bool | prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list) |
virtual bool | prepareSwitch (const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list) |
virtual void | read (const ros::Time &time, const ros::Duration &period) |
virtual void | read (const ros::Time &time, const ros::Duration &period) |
RobotHW () | |
virtual void | write (const ros::Time &time, const ros::Duration &period) |
virtual void | write (const ros::Time &time, const ros::Duration &period) |
virtual | ~RobotHW () |
Public Member Functions inherited from hardware_interface::InterfaceManager | |
T * | get () |
std::vector< std::string > | getInterfaceResources (std::string iface_type) const |
std::vector< std::string > | getNames () const |
void | registerInterface (T *iface) |
void | registerInterfaceManager (InterfaceManager *iface_man) |
Static Public Member Functions | |
static void | OnHommingCompletedCB () |
int MsgPublisher_RobotError(); 현재 미사용 : DRHWInterface::OnLogAlarm 에서 바로 퍼블리싱 함. More... | |
static void | OnLogAlarm (LPLOG_ALARM pLogAlarm) |
static void | OnMonitoringAccessControlCB (const MONITORING_ACCESS_CONTROL eAccCtrl) |
static void | OnMonitoringCtrlIOCB (const LPMONITORING_CTRLIO pCtrlIO) |
static void | OnMonitoringDataCB (const LPMONITORING_DATA pData) |
static void | OnMonitoringModbusCB (const LPMONITORING_MODBUS pModbus) |
static void | OnMonitoringStateCB (const ROBOT_STATE eState) |
static void | OnProgramStoppedCB (const PROGRAM_STOP_CAUSE iStopCause) |
static void | OnTpInitializingCompletedCB () |
Private Member Functions | |
bool | config_create_modbus_cb (dsr_msgs::ConfigCreateModbus::Request &req, dsr_msgs::ConfigCreateModbus::Response &res) |
bool | config_create_tcp_cb (dsr_msgs::ConfigCreateTcp::Request &req, dsr_msgs::ConfigCreateTcp::Response &res) |
bool | config_create_tool_cb (dsr_msgs::ConfigCreateTool::Request &req, dsr_msgs::ConfigCreateTool::Response &res) |
bool | config_delete_modbus_cb (dsr_msgs::ConfigDeleteModbus::Request &req, dsr_msgs::ConfigDeleteModbus::Response &res) |
bool | config_delete_tcp_cb (dsr_msgs::ConfigDeleteTcp::Request &req, dsr_msgs::ConfigDeleteTcp::Response &res) |
bool | config_delete_tool_cb (dsr_msgs::ConfigDeleteTool::Request &req, dsr_msgs::ConfigDeleteTool::Response &res) |
bool | drl_pause_cb (dsr_msgs::DrlPause::Request &req, dsr_msgs::DrlPause::Response &res) |
bool | drl_resume_cb (dsr_msgs::DrlResume::Request &req, dsr_msgs::DrlResume::Response &res) |
bool | drl_start_cb (dsr_msgs::DrlStart::Request &req, dsr_msgs::DrlStart::Response &res) |
bool | drl_stop_cb (dsr_msgs::DrlStop::Request &req, dsr_msgs::DrlStop::Response &res) |
bool | get_analog_input_cb (dsr_msgs::GetCtrlBoxAnalogInput::Request &req, dsr_msgs::GetCtrlBoxAnalogInput::Response &res) |
bool | get_current_tcp_cb (dsr_msgs::GetCurrentTcp::Request &req, dsr_msgs::GetCurrentTcp::Response &res) |
bool | get_current_tool_cb (dsr_msgs::GetCurrentTool::Request &req, dsr_msgs::GetCurrentTool::Response &res) |
bool | get_digital_input_cb (dsr_msgs::GetCtrlBoxDigitalInput::Request &req, dsr_msgs::GetCtrlBoxDigitalInput::Response &res) |
bool | get_drl_state_cb (dsr_msgs::GetDrlState::Request &req, dsr_msgs::GetDrlState::Response &res) |
bool | get_modbus_input_cb (dsr_msgs::GetModbusInput::Request &req, dsr_msgs::GetModbusInput::Response &res) |
bool | get_robot_mode_cb (dsr_msgs::GetRobotMode::Request &req, dsr_msgs::GetRobotMode::Response &res) |
bool | get_tool_digital_input_cb (dsr_msgs::GetToolDigitalInput::Request &req, dsr_msgs::GetToolDigitalInput::Response &res) |
bool | moveb_cb (dsr_msgs::MoveBlending::Request &req, dsr_msgs::MoveBlending::Response &res) |
bool | movec_cb (dsr_msgs::MoveCircle::Request &req, dsr_msgs::MoveCircle::Response &res) |
bool | movej_cb (dsr_msgs::MoveJoint::Request &req, dsr_msgs::MoveJoint::Response &res) |
bool | movejx_cb (dsr_msgs::MoveJointx::Request &req, dsr_msgs::MoveJointx::Response &res) |
bool | movel_cb (dsr_msgs::MoveLine::Request &req, dsr_msgs::MoveLine::Response &res) |
bool | moveperiodic_cb (dsr_msgs::MovePeriodic::Request &req, dsr_msgs::MovePeriodic::Response &res) |
bool | movesj_cb (dsr_msgs::MoveSplineJoint::Request &req, dsr_msgs::MoveSplineJoint::Response &res) |
bool | movespiral_cb (dsr_msgs::MoveSpiral::Request &req, dsr_msgs::MoveSpiral::Response &res) |
bool | movesx_cb (dsr_msgs::MoveSplineTask::Request &req, dsr_msgs::MoveSplineTask::Response &res) |
bool | movewait_cb (dsr_msgs::MoveWait::Request &req, dsr_msgs::MoveWait::Response &res) |
void | positionCallback (const std_msgs::Float64MultiArray::ConstPtr &msg) |
bool | robotiq_2f_close_cb (dsr_msgs::Robotiq2FClose::Request &req, dsr_msgs::Robotiq2FClose::Response &res) |
bool | robotiq_2f_move_cb (dsr_msgs::Robotiq2FMove::Request &req, dsr_msgs::Robotiq2FMove::Response &res) |
bool | robotiq_2f_open_cb (dsr_msgs::Robotiq2FOpen::Request &req, dsr_msgs::Robotiq2FOpen::Response &res) |
bool | serial_send_data_cb (dsr_msgs::SerialSendData::Request &req, dsr_msgs::SerialSendData::Response &res) |
bool | set_analog_input_type_cb (dsr_msgs::SetCtrlBoxAnalogInputType::Request &req, dsr_msgs::SetCtrlBoxAnalogInputType::Response &res) |
bool | set_analog_output_cb (dsr_msgs::SetCtrlBoxAnalogOutput::Request &req, dsr_msgs::SetCtrlBoxAnalogOutput::Response &res) |
bool | set_analog_output_type_cb (dsr_msgs::SetCtrlBoxAnalogOutputType::Request &req, dsr_msgs::SetCtrlBoxAnalogOutputType::Response &res) |
bool | set_current_tcp_cb (dsr_msgs::SetCurrentTcp::Request &req, dsr_msgs::SetCurrentTcp::Response &res) |
bool | set_current_tool_cb (dsr_msgs::SetCurrentTool::Request &req, dsr_msgs::SetCurrentTool::Response &res) |
bool | set_digital_output_cb (dsr_msgs::SetCtrlBoxDigitalOutput::Request &req, dsr_msgs::SetCtrlBoxDigitalOutput::Response &res) |
bool | set_modbus_output_cb (dsr_msgs::SetModbusOutput::Request &req, dsr_msgs::SetModbusOutput::Response &res) |
bool | set_robot_mode_cb (dsr_msgs::SetRobotMode::Request &req, dsr_msgs::SetRobotMode::Response &res) |
bool | set_tool_digital_output_cb (dsr_msgs::SetToolDigitalOutput::Request &req, dsr_msgs::SetToolDigitalOutput::Response &res) |
void | sigint_handler (int signo) |
void | trajectoryCallback (const control_msgs::FollowJointTrajectoryActionGoal::ConstPtr &msg) |
Static Private Member Functions | |
static void | thread_publisher (DRHWInterface *pDRHWInterface, ros::NodeHandle nh, int nPubRate) |
static void | thread_subscribe (ros::NodeHandle nh) |
Additional Inherited Members | |
Protected Types inherited from hardware_interface::InterfaceManager | |
typedef std::vector< InterfaceManager * > | InterfaceManagerVector |
typedef std::map< std::string, void * > | InterfaceMap |
typedef std::map< std::string, std::vector< std::string > > | ResourceMap |
typedef std::map< std::string, size_t > | SizeMap |
Protected Attributes inherited from hardware_interface::InterfaceManager | |
boost::ptr_vector< ResourceManagerBase > | interface_destruction_list_ |
InterfaceManagerVector | interface_managers_ |
InterfaceMap | interfaces_ |
InterfaceMap | interfaces_combo_ |
SizeMap | num_ifaces_registered_ |
ResourceMap | resources_ |
Definition at line 198 of file dsr_hw_interface.h.
dsr_control::DRHWInterface::DRHWInterface | ( | ros::NodeHandle & | nh | ) |
Definition at line 465 of file dsr_hw_interface.cpp.
|
virtual |
Definition at line 600 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1049 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1093 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1115 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1054 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1100 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1124 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1059 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1074 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1064 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1069 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1024 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1088 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1110 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1004 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1079 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1044 of file dsr_hw_interface.cpp.
|
private |
Definition at line 801 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1014 of file dsr_hw_interface.cpp.
bool dsr_control::DRHWInterface::init | ( | ) |
Definition at line 613 of file dsr_hw_interface.cpp.
|
private |
Definition at line 919 of file dsr_hw_interface.cpp.
|
private |
ROS_INFO(" <xxx pos1> %7.3f %7.3f %7.3f %7.3f %7.3f %7.3f",fTargetPos[0][0],fTargetPos[0][1],fTargetPos[0][2],fTargetPos[0][3],fTargetPos[0][4],fTargetPos[0][5]); ROS_INFO(" <xxx pos2> %7.3f %7.3f %7.3f %7.3f %7.3f %7.3f",fTargetPos[1][0],fTargetPos[1][1],fTargetPos[1][2],fTargetPos[1][3],fTargetPos[1][4],fTargetPos[1][5]);
Definition at line 849 of file dsr_hw_interface.cpp.
|
private |
Definition at line 805 of file dsr_hw_interface.cpp.
|
private |
Definition at line 836 of file dsr_hw_interface.cpp.
|
private |
Definition at line 818 of file dsr_hw_interface.cpp.
|
private |
Definition at line 977 of file dsr_hw_interface.cpp.
|
private |
Definition at line 873 of file dsr_hw_interface.cpp.
|
private |
Definition at line 961 of file dsr_hw_interface.cpp.
|
private |
Definition at line 892 of file dsr_hw_interface.cpp.
|
private |
Definition at line 993 of file dsr_hw_interface.cpp.
int dsr_control::DRHWInterface::MsgPublisher_RobotState | ( | ) |
printf("[%s,%s] msg.robot_state_str =%s m_stDrState.strRobotState=%s\n",m_strRobotName.c_str(),m_strRobotModel.c_str(),msg.robot_state_str.c_str(),m_stDrState.strRobotState);
Definition at line 345 of file dsr_hw_interface.cpp.
|
static |
int MsgPublisher_RobotError(); 현재 미사용 : DRHWInterface::OnLogAlarm 에서 바로 퍼블리싱 함.
Definition at line 86 of file dsr_hw_interface.cpp.
|
static |
Definition at line 300 of file dsr_hw_interface.cpp.
|
static |
Definition at line 268 of file dsr_hw_interface.cpp.
|
static |
Definition at line 101 of file dsr_hw_interface.cpp.
|
static |
Definition at line 121 of file dsr_hw_interface.cpp.
|
static |
Definition at line 111 of file dsr_hw_interface.cpp.
|
static |
Definition at line 213 of file dsr_hw_interface.cpp.
|
static |
Definition at line 95 of file dsr_hw_interface.cpp.
|
static |
Definition at line 75 of file dsr_hw_interface.cpp.
|
private |
Definition at line 727 of file dsr_hw_interface.cpp.
|
virtual |
Definition at line 674 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1172 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1132 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1158 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1187 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1034 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1019 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1029 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1083 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1105 of file dsr_hw_interface.cpp.
|
private |
Definition at line 999 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1039 of file dsr_hw_interface.cpp.
|
private |
Definition at line 797 of file dsr_hw_interface.cpp.
|
private |
Definition at line 1009 of file dsr_hw_interface.cpp.
|
private |
Definition at line 721 of file dsr_hw_interface.cpp.
|
staticprivate |
Definition at line 450 of file dsr_hw_interface.cpp.
|
staticprivate |
Definition at line 441 of file dsr_hw_interface.cpp.
|
private |
ROS_INFO("[trajectory] preTargetTime: %7.3f", preTargetTime); targetTime = targetTime - preTargetTime; preTargetTime = targetTime; ROS_INFO("[trajectory] time_from_start: %7.3f", targetTime);
Definition at line 734 of file dsr_hw_interface.cpp.
|
virtual |
Definition at line 690 of file dsr_hw_interface.cpp.
|
private |
Definition at line 256 of file dsr_hw_interface.h.
|
private |
Definition at line 255 of file dsr_hw_interface.h.
|
private |
Definition at line 252 of file dsr_hw_interface.h.
|
private |
Definition at line 251 of file dsr_hw_interface.h.
|
private |
|
private |
Definition at line 233 of file dsr_hw_interface.h.
|
private |
Definition at line 236 of file dsr_hw_interface.h.
|
private |
Definition at line 231 of file dsr_hw_interface.h.
|
private |
Definition at line 232 of file dsr_hw_interface.h.
|
private |
Definition at line 230 of file dsr_hw_interface.h.
|
private |
Definition at line 237 of file dsr_hw_interface.h.
|
private |
Definition at line 229 of file dsr_hw_interface.h.
|
private |
Definition at line 234 of file dsr_hw_interface.h.
|
private |
Definition at line 235 of file dsr_hw_interface.h.
|
private |
Definition at line 241 of file dsr_hw_interface.h.
|
private |
Definition at line 240 of file dsr_hw_interface.h.
|
private |
Definition at line 243 of file dsr_hw_interface.h.
|
private |
Definition at line 242 of file dsr_hw_interface.h.
|
private |
Definition at line 277 of file dsr_hw_interface.h.
|
private |
Definition at line 276 of file dsr_hw_interface.h.
|
private |
Definition at line 226 of file dsr_hw_interface.h.
|
private |
Definition at line 225 of file dsr_hw_interface.h.
|
private |
Definition at line 224 of file dsr_hw_interface.h.
|
private |
Definition at line 247 of file dsr_hw_interface.h.
|
private |
Definition at line 246 of file dsr_hw_interface.h.
|
private |
Definition at line 248 of file dsr_hw_interface.h.
|
private |
Definition at line 272 of file dsr_hw_interface.h.
|
private |
Definition at line 271 of file dsr_hw_interface.h.
|
private |
Definition at line 222 of file dsr_hw_interface.h.
|
private |
Definition at line 253 of file dsr_hw_interface.h.