Classes | Public Member Functions | Public Attributes
NodeClass Class Reference

List of all members.

Classes

struct  ParamType

Public Member Functions

bool initDrives ()
 NodeClass ()
void publish_globalDiagnostics (const ros::TimerEvent &event)
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 (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
bool srvCallback_Recover (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
bool srvCallback_Shutdown (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
void topicCallback_JointStateCmd (const control_msgs::JointTrajectoryControllerState::ConstPtr &msg)
 ~NodeClass ()

Public Attributes

ros::Timer glDiagnostics_timer
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_DiagnosticGlobal_
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 51 of file cob_base_drive_chain.cpp.


Constructor & Destructor Documentation

NodeClass::NodeClass ( ) [inline]

Parameters are set within the launch file

Definition at line 163 of file cob_base_drive_chain.cpp.

NodeClass::~NodeClass ( ) [inline]

Definition at line 243 of file cob_base_drive_chain.cpp.


Member Function Documentation

Definition at line 820 of file cob_base_drive_chain.cpp.

void NodeClass::publish_globalDiagnostics ( const ros::TimerEvent event) [inline]

Definition at line 694 of file cob_base_drive_chain.cpp.

bool NodeClass::publish_JointStates ( ) [inline]

Definition at line 516 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 431 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 447 of file cob_base_drive_chain.cpp.

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

Definition at line 402 of file cob_base_drive_chain.cpp.

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

Definition at line 470 of file cob_base_drive_chain.cpp.

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

Definition at line 498 of file cob_base_drive_chain.cpp.

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

Definition at line 254 of file cob_base_drive_chain.cpp.


Member Data Documentation

Timer to publish global diagnostic messages

Definition at line 75 of file cob_base_drive_chain.cpp.

Definition at line 145 of file cob_base_drive_chain.cpp.

Definition at line 159 of file cob_base_drive_chain.cpp.

Definition at line 160 of file cob_base_drive_chain.cpp.

Definition at line 143 of file cob_base_drive_chain.cpp.

Definition at line 147 of file cob_base_drive_chain.cpp.

Definition at line 146 of file cob_base_drive_chain.cpp.

Definition at line 156 of file cob_base_drive_chain.cpp.

Definition at line 55 of file cob_base_drive_chain.cpp.

Definition at line 158 of file cob_base_drive_chain.cpp.

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 106 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 122 of file cob_base_drive_chain.cpp.

Service requests std_srvs::Trigger and initializes platform and motors

Definition at line 87 of file cob_base_drive_chain.cpp.

Service requests std_srvs::Trigger and resets platform and motors

Definition at line 92 of file cob_base_drive_chain.cpp.

Definition at line 99 of file cob_base_drive_chain.cpp.

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

Definition at line 97 of file cob_base_drive_chain.cpp.

Definition at line 63 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 70 of file cob_base_drive_chain.cpp.

Definition at line 64 of file cob_base_drive_chain.cpp.

On this topic "JointState" of type sensor_msgs::JointState the node publishes joint states

Definition at line 61 of file cob_base_drive_chain.cpp.

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

Definition at line 81 of file cob_base_drive_chain.cpp.


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


cob_base_drive_chain
Author(s): Christian Connette
autogenerated on Sat Jun 8 2019 21:02:30