NodeClass Class Reference

List of all members.

Classes

struct  ParamType

Public Member Functions

bool initDrives ()
 NodeClass ()
bool publish_JointStates ()
bool srvCallback_ElmoRecorderConfig (cob_base_drive_chain::ElmoRecorderConfig::Request &req, cob_base_drive_chain::ElmoRecorderConfig::Response &res)
bool srvCallback_ElmoRecorderReadout (cob_base_drive_chain::ElmoRecorderReadout::Request &req, cob_base_drive_chain::ElmoRecorderReadout::Response &res)
bool srvCallback_Init (cob_srvs::Trigger::Request &req, cob_srvs::Trigger::Response &res)
bool srvCallback_Recover (cob_srvs::Trigger::Request &req, cob_srvs::Trigger::Response &res)
bool srvCallback_Shutdown (cob_srvs::Trigger::Request &req, cob_srvs::Trigger::Response &res)
void topicCallback_JointStateCmd (const pr2_controllers_msgs::JointTrajectoryControllerState::ConstPtr &msg)
 ~NodeClass ()

Public Attributes

bool m_bisInitialized
bool m_bPubEffort
bool m_bReadoutElmo
CanCtrlPltfCOb3m_CanCtrlPltf
int m_iNumDrives
int m_iNumMotors
ParamType m_Param
ros::NodeHandle n
std::string sIniDirectory
ros::ServiceServer srvServer_ElmoRecorderConfig
ros::ServiceServer srvServer_ElmoRecorderReadout
ros::ServiceServer srvServer_Init
ros::ServiceServer srvServer_Recover
ros::ServiceServer srvServer_SetMotionType
ros::ServiceServer srvServer_Shutdown
ros::Publisher topicPub_ControllerState
ros::Publisher topicPub_Diagnostic
ros::Publisher topicPub_JointState
ros::Subscriber topicSub_JointStateCmd

Detailed Description

This node provides control of the care-o-bot platform drives to the ROS-"network". For this purpose it offers several services and publishes data on different topics.

Definition at line 87 of file cob_base_drive_chain.cpp.


Constructor & Destructor Documentation

NodeClass::NodeClass (  )  [inline]

Parameters are set within the launch file

Definition at line 199 of file cob_base_drive_chain.cpp.

NodeClass::~NodeClass (  )  [inline]

Definition at line 284 of file cob_base_drive_chain.cpp.


Member Function Documentation

bool NodeClass::initDrives (  ) 

Definition at line 895 of file cob_base_drive_chain.cpp.

bool NodeClass::publish_JointStates (  )  [inline]

Definition at line 558 of file cob_base_drive_chain.cpp.

bool NodeClass::srvCallback_ElmoRecorderConfig ( cob_base_drive_chain::ElmoRecorderConfig::Request req,
cob_base_drive_chain::ElmoRecorderConfig::Response res 
) [inline]

Definition at line 472 of file cob_base_drive_chain.cpp.

bool NodeClass::srvCallback_ElmoRecorderReadout ( cob_base_drive_chain::ElmoRecorderReadout::Request req,
cob_base_drive_chain::ElmoRecorderReadout::Response res 
) [inline]

Definition at line 488 of file cob_base_drive_chain.cpp.

bool NodeClass::srvCallback_Init ( cob_srvs::Trigger::Request &  req,
cob_srvs::Trigger::Response &  res 
) [inline]

Definition at line 443 of file cob_base_drive_chain.cpp.

bool NodeClass::srvCallback_Recover ( cob_srvs::Trigger::Request &  req,
cob_srvs::Trigger::Response &  res 
) [inline]

Definition at line 511 of file cob_base_drive_chain.cpp.

bool NodeClass::srvCallback_Shutdown ( cob_srvs::Trigger::Request &  req,
cob_srvs::Trigger::Response &  res 
) [inline]

Definition at line 540 of file cob_base_drive_chain.cpp.

void NodeClass::topicCallback_JointStateCmd ( const pr2_controllers_msgs::JointTrajectoryControllerState::ConstPtr &  msg  )  [inline]

Definition at line 295 of file cob_base_drive_chain.cpp.


Member Data Documentation

Definition at line 181 of file cob_base_drive_chain.cpp.

Definition at line 195 of file cob_base_drive_chain.cpp.

Definition at line 196 of file cob_base_drive_chain.cpp.

Definition at line 179 of file cob_base_drive_chain.cpp.

Definition at line 183 of file cob_base_drive_chain.cpp.

Definition at line 182 of file cob_base_drive_chain.cpp.

Definition at line 192 of file cob_base_drive_chain.cpp.

ros::NodeHandle NodeClass::n

Definition at line 84 of file cob_base_drive_chain.cpp.

Definition at line 194 of file cob_base_drive_chain.cpp.

Service requests cob_base_drive_chain::GetJointState. It reads out the latest joint information from the CAN buffer and gives it back. It also publishes the informaion on the topic "JointState" Service requests cob_base_drive_chain::ElmoRecorderSetup. It is used to configure the Elmo Recorder to record predefined sources. Parameters are: int64 recordinggap Specify every which time quantum (4*90usec) a new data point (of 1024 points in total) is recorded. the recording process starts immediately.

Definition at line 135 of file cob_base_drive_chain.cpp.

Service requests cob_base_drive_chain::ElmoRecorderGet. It is used to start the read-out process of previously recorded data by the Elmo Recorder. Parameters are: int64 subindex As Subindex, set the recorded source you want to read out: #1: Main Speed #2: Main Position #10: ActiveCurrent #16: Speed Command

string fileprefix Enter the path+file-prefix for the logfile (of an existing directory!) The file-prefix is extended with _MotorNumber_RecordedSource.log

Definition at line 151 of file cob_base_drive_chain.cpp.

ros::ServiceServer NodeClass::srvServer_Init

Service requests cob_srvs::Trigger and initializes platform and motors

Definition at line 111 of file cob_base_drive_chain.cpp.

ros::ServiceServer NodeClass::srvServer_Recover

Service requests cob_srvs::Trigger and resets platform and motors

Definition at line 116 of file cob_base_drive_chain.cpp.

Definition at line 123 of file cob_base_drive_chain.cpp.

ros::ServiceServer NodeClass::srvServer_Shutdown

Service requests cob_srvs::Trigger and shuts down platform and motors

Definition at line 121 of file cob_base_drive_chain.cpp.

Definition at line 92 of file cob_base_drive_chain.cpp.

On this topic "Diagnostic" of type diagnostic_msgs::DiagnosticStatus the node publishes states and error information about the platform.

Definition at line 98 of file cob_base_drive_chain.cpp.

On this topic "JointState" of type sensor_msgs::JointState the node publishes joint states when they are requested over the appropriate service srvServer_GetJointState.

Definition at line 90 of file cob_base_drive_chain.cpp.

The node subscribes to the topic "JointStateCmd" and performs the requested motor commands

Definition at line 105 of file cob_base_drive_chain.cpp.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator


cob_base_drive_chain
Author(s): Christian Connette
autogenerated on Fri Jan 11 09:42:35 2013