Classes | Public Member Functions | Public Attributes | Private Types | Private Attributes
DensoController Class Reference
Inheritance diagram for DensoController:
Inheritance graph
[legend]

List of all members.

Classes

class  DensoControllerStatus

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 bCapReflectRealState ()
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 ()
 DensoController ()
virtual void finalizeHW ()
void initializeCM ()
void initializeHW ()
void initializeROS (ros::NodeHandle &node)
void quitRequest ()
OpenControllersInterface::ControllerStatusPtr recoverController ()
void setUDPTimeout (long sec, long usec)
void start ()
OpenControllersInterface::ControllerStatusPtr updateJoints (struct timespec *spec_result)
virtual ~DensoController ()

Public Attributes

u_int __errorcode__

Private Types

typedef boost::shared_ptr
< DensoControllerStatus
DensoControllerStatusPtr

Private Attributes

char errdesc_buffer_ [2048]
int iSockFD_
u_int lhController_
u_int lhRobot_
std::vector< double > prev_angle_
struct timespec prev_time_
std::vector< double > prev_vel_
std::string server_ip_address_
int server_port_number_
int udp_timeout_
std::map< std::string, u_int > var_handlers_
std::map< std::string, u_short > var_types_

Detailed Description

Definition at line 82 of file main.cpp.


Member Typedef Documentation

Definition at line 94 of file main.cpp.


Constructor & Destructor Documentation

Definition at line 97 of file main.cpp.

virtual DensoController::~DensoController ( ) [inline, virtual]

Definition at line 108 of file main.cpp.


Member Function Documentation

BCAP_HRESULT DensoController::bCapClearError ( ) [inline]

Definition at line 163 of file main.cpp.

BCAP_HRESULT DensoController::bCapClose ( ) [inline]

Definition at line 141 of file main.cpp.

BCAP_HRESULT DensoController::bCapControllerConnect ( ) [inline]

Definition at line 148 of file main.cpp.

BCAP_HRESULT DensoController::bCapControllerDisConnect ( ) [inline]

Definition at line 156 of file main.cpp.

u_int DensoController::bCapControllerGetVariable ( const std::string &  varname) [inline]

Definition at line 273 of file main.cpp.

BCAP_HRESULT DensoController::bCapCurJnt ( std::vector< double > &  jointvalues) [inline]

Definition at line 406 of file main.cpp.

u_int DensoController::bCapErrorDescription ( std::string &  errormsg) [inline]

Definition at line 353 of file main.cpp.

BCAP_HRESULT DensoController::bCapFillBuffer ( ) [inline]

Definition at line 552 of file main.cpp.

bool DensoController::bCapGetBoolVariable ( const std::string &  var_name) [inline]

Definition at line 295 of file main.cpp.

Definition at line 348 of file main.cpp.

Definition at line 326 of file main.cpp.

u_int DensoController::bCapGetIntegerVariable ( const std::string &  var_name) [inline]

Definition at line 310 of file main.cpp.

u_int DensoController::bCapGetMode ( ) [inline]

Definition at line 343 of file main.cpp.

BCAP_HRESULT DensoController::bCapGetRobot ( ) [inline]

Definition at line 172 of file main.cpp.

BCAP_HRESULT DensoController::bCapGiveArm ( ) [inline]

Definition at line 209 of file main.cpp.

Definition at line 233 of file main.cpp.

BCAP_HRESULT DensoController::bCapMotor ( bool  command) [inline]

Definition at line 381 of file main.cpp.

BCAP_HRESULT DensoController::bCapOpen ( ) [inline]

Open a bCap socket.

Definition at line 134 of file main.cpp.

BCAP_HRESULT DensoController::bCapReflectRealState ( ) [inline]

Definition at line 575 of file main.cpp.

BCAP_HRESULT DensoController::bCapReleaseRobot ( ) [inline]

Definition at line 180 of file main.cpp.

BCAP_HRESULT DensoController::bCapRobotExecute ( char *  command,
char *  arg 
) [inline]

Definition at line 187 of file main.cpp.

u_int DensoController::bCapRobotGetVariable ( const std::string &  varname) [inline]

Definition at line 284 of file main.cpp.

BCAP_HRESULT DensoController::bCapRobotSlvMove ( BCAP_VARIANT *  pose,
BCAP_VARIANT *  result 
) [inline]

Definition at line 428 of file main.cpp.

BCAP_HRESULT DensoController::bCapServerStart ( ) [inline]

Definition at line 1151 of file main.cpp.

BCAP_HRESULT DensoController::bCapServerStop ( ) [inline]

Definition at line 1156 of file main.cpp.

BCAP_HRESULT DensoController::bCapSetExternalSpeed ( float  arg) [inline]

Definition at line 217 of file main.cpp.

BCAP_HRESULT DensoController::bCapSlvChangeMode ( u_int  arg) [inline]

Definition at line 414 of file main.cpp.

BCAP_HRESULT DensoController::bCapTakearm ( ) [inline]

Definition at line 195 of file main.cpp.

virtual void DensoController::finalizeHW ( ) [inline, virtual]

Implements OpenControllersInterface::OpenController.

Definition at line 591 of file main.cpp.

void DensoController::initializeCM ( ) [inline, virtual]

Implements OpenControllersInterface::OpenController.

Definition at line 1165 of file main.cpp.

void DensoController::initializeHW ( ) [inline, virtual]

Implements OpenControllersInterface::OpenController.

Definition at line 1183 of file main.cpp.

void DensoController::initializeROS ( ros::NodeHandle node) [inline, virtual]

Implements OpenControllersInterface::OpenController.

Definition at line 1304 of file main.cpp.

void DensoController::quitRequest ( ) [inline, virtual]

Reimplemented from OpenControllersInterface::OpenController.

Definition at line 1337 of file main.cpp.

Implements OpenControllersInterface::OpenController.

Definition at line 805 of file main.cpp.

void DensoController::setUDPTimeout ( long  sec,
long  usec 
) [inline]

Definition at line 1134 of file main.cpp.

void DensoController::start ( ) [inline]

Reimplemented from OpenControllersInterface::OpenController.

Definition at line 110 of file main.cpp.

OpenControllersInterface::ControllerStatusPtr DensoController::updateJoints ( struct timespec *  spec_result) [inline, virtual]

Implements OpenControllersInterface::OpenController.

Definition at line 676 of file main.cpp.


Member Data Documentation

Definition at line 325 of file main.cpp.

char DensoController::errdesc_buffer_[2048] [private]

Definition at line 124 of file main.cpp.

Definition at line 118 of file main.cpp.

Definition at line 119 of file main.cpp.

u_int DensoController::lhRobot_ [private]

Definition at line 120 of file main.cpp.

Definition at line 126 of file main.cpp.

struct timespec DensoController::prev_time_ [private]

Definition at line 128 of file main.cpp.

Definition at line 127 of file main.cpp.

std::string DensoController::server_ip_address_ [private]

Definition at line 115 of file main.cpp.

Definition at line 116 of file main.cpp.

Definition at line 121 of file main.cpp.

std::map<std::string, u_int> DensoController::var_handlers_ [private]

Definition at line 122 of file main.cpp.

std::map<std::string, u_short> DensoController::var_types_ [private]

Definition at line 123 of file main.cpp.


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


denso_controller
Author(s): Ryohei Ueda
autogenerated on Thu Jun 6 2019 20:15:20