Public Member Functions | Public Attributes | Private Attributes | List of all members
DensoRobot Class Reference

#include <denso_robot.h>

Public Member Functions

BCAP_HRESULT bCapClearError ()
 
BCAP_HRESULT bCapClose ()
 
BCAP_HRESULT bCapControllerConnect ()
 
BCAP_HRESULT bCapControllerDisConnect ()
 
u_int bCapControllerGetVariable (const std::string &varname)
 
BCAP_HRESULT bCapCurJnt (std::vector< double > &jointvalues)
 
u_int bCapErrorDescription (std::string &errormsg)
 
BCAP_HRESULT bCapFillBuffer ()
 
bool bCapGetBoolVariable (const std::string &var_name)
 
bool bCapGetEmergencyStop ()
 
u_int bCapGetErrorCode ()
 
u_int bCapGetIntegerVariable (const std::string &var_name)
 
u_int bCapGetMode ()
 
BCAP_HRESULT bCapGetRobot ()
 
BCAP_HRESULT bCapGiveArm ()
 
void bCapInitializeVariableHandlers ()
 
BCAP_HRESULT bCapMotor (bool command)
 
BCAP_HRESULT bCapOpen ()
 
BCAP_HRESULT bCapReleaseRobot ()
 
BCAP_HRESULT bCapRobotExecute (char *command, char *arg)
 
u_int bCapRobotGetVariable (const std::string &varname)
 
BCAP_HRESULT bCapRobotSlvMove (BCAP_VARIANT *pose, BCAP_VARIANT *result)
 
BCAP_HRESULT bCapServerStart ()
 
BCAP_HRESULT bCapServerStop ()
 
BCAP_HRESULT bCapSetExternalSpeed (float arg)
 
BCAP_HRESULT bCapSlvChangeMode (u_int arg)
 
BCAP_HRESULT bCapTakearm ()
 
 DensoRobot ()
 
virtual void finalizeHW ()
 
bool initialize (ros::NodeHandle &node, int num_joints)
 
bool read (std::vector< double > &pos)
 
void setUDPTimeout (long sec, long usec)
 
bool write (const std::vector< double > &cmd, std::vector< double > &pos)
 
virtual ~DensoRobot ()
 

Public Attributes

u_int __errorcode__
 

Private Attributes

bool dryrunp_
 
char errdesc_buffer_ [2048]
 
int iSockFD_
 
std::vector< double > jntvalues_
 
u_int lhController_
 
u_int lhRobot_
 
int num_joints_
 
struct timespec prev_time_
 
std::string server_ip_address_
 
int server_port_number_
 
int udp_timeout_
 
std::map< std::string, u_intvar_handlers_
 
std::map< std::string, u_shortvar_types_
 

Detailed Description

Definition at line 27 of file denso_robot.h.

Constructor & Destructor Documentation

DensoRobot::DensoRobot ( )
inline

Definition at line 30 of file denso_robot.h.

virtual DensoRobot::~DensoRobot ( )
inlinevirtual

Definition at line 35 of file denso_robot.h.

Member Function Documentation

BCAP_HRESULT DensoRobot::bCapClearError ( )
inline

Definition at line 69 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapClose ( )
inline

Definition at line 47 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapControllerConnect ( )
inline

Definition at line 54 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapControllerDisConnect ( )
inline

Definition at line 62 of file denso_robot.h.

u_int DensoRobot::bCapControllerGetVariable ( const std::string &  varname)
inline

Definition at line 178 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapCurJnt ( std::vector< double > &  jointvalues)
inline

Definition at line 311 of file denso_robot.h.

u_int DensoRobot::bCapErrorDescription ( std::string &  errormsg)
inline

Definition at line 258 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapFillBuffer ( )
inline

Definition at line 371 of file denso_robot.h.

bool DensoRobot::bCapGetBoolVariable ( const std::string &  var_name)
inline

Definition at line 200 of file denso_robot.h.

bool DensoRobot::bCapGetEmergencyStop ( )
inline

Definition at line 253 of file denso_robot.h.

u_int DensoRobot::bCapGetErrorCode ( )
inline

Definition at line 231 of file denso_robot.h.

u_int DensoRobot::bCapGetIntegerVariable ( const std::string &  var_name)
inline

Definition at line 215 of file denso_robot.h.

u_int DensoRobot::bCapGetMode ( )
inline

Definition at line 248 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapGetRobot ( )
inline

Definition at line 78 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapGiveArm ( )
inline

Definition at line 114 of file denso_robot.h.

void DensoRobot::bCapInitializeVariableHandlers ( )
inline

Definition at line 138 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapMotor ( bool  command)
inline

Definition at line 286 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapOpen ( )
inline

Definition at line 40 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapReleaseRobot ( )
inline

Definition at line 85 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapRobotExecute ( char *  command,
char *  arg 
)
inline

Definition at line 92 of file denso_robot.h.

u_int DensoRobot::bCapRobotGetVariable ( const std::string &  varname)
inline

Definition at line 189 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapRobotSlvMove ( BCAP_VARIANT pose,
BCAP_VARIANT result 
)
inline

Definition at line 338 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapServerStart ( )
inline

Definition at line 1019 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapServerStop ( )
inline

Definition at line 1024 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapSetExternalSpeed ( float  arg)
inline

Definition at line 122 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapSlvChangeMode ( u_int  arg)
inline

Definition at line 324 of file denso_robot.h.

BCAP_HRESULT DensoRobot::bCapTakearm ( )
inline

Definition at line 100 of file denso_robot.h.

virtual void DensoRobot::finalizeHW ( )
inlinevirtual

Definition at line 422 of file denso_robot.h.

bool DensoRobot::initialize ( ros::NodeHandle node,
int  num_joints 
)
inline

Definition at line 1030 of file denso_robot.h.

bool DensoRobot::read ( std::vector< double > &  pos)
inline

Definition at line 505 of file denso_robot.h.

void DensoRobot::setUDPTimeout ( long  sec,
long  usec 
)
inline

Definition at line 1002 of file denso_robot.h.

bool DensoRobot::write ( const std::vector< double > &  cmd,
std::vector< double > &  pos 
)
inline

Definition at line 521 of file denso_robot.h.

Member Data Documentation

u_int DensoRobot::__errorcode__

Definition at line 230 of file denso_robot.h.

bool DensoRobot::dryrunp_
private

Definition at line 1207 of file denso_robot.h.

char DensoRobot::errdesc_buffer_[2048]
private

Definition at line 1206 of file denso_robot.h.

int DensoRobot::iSockFD_
private

Definition at line 1200 of file denso_robot.h.

std::vector<double> DensoRobot::jntvalues_
private

Definition at line 1196 of file denso_robot.h.

u_int DensoRobot::lhController_
private

Definition at line 1201 of file denso_robot.h.

u_int DensoRobot::lhRobot_
private

Definition at line 1202 of file denso_robot.h.

int DensoRobot::num_joints_
private

Definition at line 1208 of file denso_robot.h.

struct timespec DensoRobot::prev_time_
private

Definition at line 1210 of file denso_robot.h.

std::string DensoRobot::server_ip_address_
private

Definition at line 1197 of file denso_robot.h.

int DensoRobot::server_port_number_
private

Definition at line 1198 of file denso_robot.h.

int DensoRobot::udp_timeout_
private

Definition at line 1203 of file denso_robot.h.

std::map<std::string, u_int> DensoRobot::var_handlers_
private

Definition at line 1204 of file denso_robot.h.

std::map<std::string, u_short> DensoRobot::var_types_
private

Definition at line 1205 of file denso_robot.h.


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


denso_ros_control
Author(s):
autogenerated on Mon Jun 10 2019 13:13:14