Implementation of ROS node for sdh. More...
Public Member Functions | |
void | diag_init (diagnostic_updater::DiagnosticStatusWrapper &stat) |
void | executeCB (const pr2_controllers_msgs::JointTrajectoryGoalConstPtr &goal) |
Executes the callback from the actionlib. | |
bool | init () |
Initializes node to get parameters, subscribe and publish to topics. | |
SdhNode (std::string name) | |
Constructor for SdhNode class. | |
bool | srvCallback_Init (cob_srvs::Trigger::Request &req, cob_srvs::Trigger::Response &res) |
Executes the service callback for init. | |
bool | srvCallback_Recover (cob_srvs::Trigger::Request &req, cob_srvs::Trigger::Response &res) |
Executes the service callback for recover. | |
bool | srvCallback_SetOperationMode (cob_srvs::SetOperationMode::Request &req, cob_srvs::SetOperationMode::Response &res) |
Executes the service callback for set_operation_mode. | |
bool | srvCallback_Stop (cob_srvs::Trigger::Request &req, cob_srvs::Trigger::Response &res) |
Executes the service callback for stop. | |
void | updateDsa () |
Main routine to update dsa. | |
void | updateSdh () |
Main routine to update sdh. | |
~SdhNode () | |
Destructor for SdhNode class. | |
Public Attributes | |
ros::NodeHandle | nh_ |
create a handle for this node, initialize node | |
Private Attributes | |
std::string | action_name_ |
actionlib::SimpleActionServer < pr2_controllers_msgs::JointTrajectoryAction > | as_ |
std::vector< int > | axes_ |
int | baudrate_ |
int | DOF_ |
SDH::cDSA * | dsa_ |
int | dsadevicenum_ |
std::string | dsadevicestring_ |
bool | hasNewGoal_ |
int | id_read_ |
int | id_write_ |
bool | isDSAInitialized_ |
bool | isInitialized_ |
std::vector< std::string > | JointNames_ |
double | pi_ |
SDH::cSDH * | sdh_ |
int | sdhdevicenum_ |
std::string | sdhdevicestring_ |
std::string | sdhdevicetype_ |
ros::ServiceServer | srvServer_Init_ |
ros::ServiceServer | srvServer_Recover_ |
ros::ServiceServer | srvServer_SetOperationMode_ |
ros::ServiceServer | srvServer_Stop_ |
std::vector < SDH::cSDH::eAxisState > | state_ |
std::vector< double > | targetAngles_ |
double | timeout_ |
ros::Publisher | topicPub_ControllerState_ |
ros::Publisher | topicPub_JointState_ |
ros::Publisher | topicPub_TactileSensor_ |
trajectory_msgs::JointTrajectory | traj_ |
diagnostic_updater::Updater | updater_ |
Implementation of ROS node for sdh.
Offers actionlib and direct command interface.
Definition at line 95 of file cob_sdh.cpp.
SdhNode::SdhNode | ( | std::string | name | ) | [inline] |
Constructor for SdhNode class.
name | Name for the actionlib server |
Definition at line 144 of file cob_sdh.cpp.
SdhNode::~SdhNode | ( | ) | [inline] |
Destructor for SdhNode class.
Definition at line 158 of file cob_sdh.cpp.
void SdhNode::diag_init | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [inline] |
Definition at line 167 of file cob_sdh.cpp.
void SdhNode::executeCB | ( | const pr2_controllers_msgs::JointTrajectoryGoalConstPtr & | goal | ) | [inline] |
Executes the callback from the actionlib.
Set the current goal to aborted after receiving a new goal and write new goal to a member variable. Wait for the goal to finish and set actionlib status to succeeded.
goal | JointTrajectoryGoal |
Definition at line 253 of file cob_sdh.cpp.
bool SdhNode::init | ( | ) | [inline] |
Initializes node to get parameters, subscribe and publish to topics.
Definition at line 180 of file cob_sdh.cpp.
bool SdhNode::srvCallback_Init | ( | cob_srvs::Trigger::Request & | req, | |
cob_srvs::Trigger::Response & | res | |||
) | [inline] |
Executes the service callback for init.
Connects to the hardware and initialized it.
req | Service request | |
res | Service response |
Definition at line 321 of file cob_sdh.cpp.
bool SdhNode::srvCallback_Recover | ( | cob_srvs::Trigger::Request & | req, | |
cob_srvs::Trigger::Response & | res | |||
) | [inline] |
Executes the service callback for recover.
Recovers the hardware after an emergency stop.
req | Service request | |
res | Service response |
Definition at line 446 of file cob_sdh.cpp.
bool SdhNode::srvCallback_SetOperationMode | ( | cob_srvs::SetOperationMode::Request & | req, | |
cob_srvs::SetOperationMode::Response & | res | |||
) | [inline] |
Executes the service callback for set_operation_mode.
Changes the operation mode.
req | Service request | |
res | Service response |
Definition at line 462 of file cob_sdh.cpp.
bool SdhNode::srvCallback_Stop | ( | cob_srvs::Trigger::Request & | req, | |
cob_srvs::Trigger::Response & | res | |||
) | [inline] |
Executes the service callback for stop.
Stops all hardware movements.
req | Service request | |
res | Service response |
Definition at line 418 of file cob_sdh.cpp.
void SdhNode::updateDsa | ( | ) | [inline] |
void SdhNode::updateSdh | ( | ) | [inline] |
Main routine to update sdh.
Sends target to hardware and reads out current configuration.
Definition at line 476 of file cob_sdh.cpp.
std::string SdhNode::action_name_ [private] |
Definition at line 103 of file cob_sdh.cpp.
actionlib::SimpleActionServer<pr2_controllers_msgs::JointTrajectoryAction> SdhNode::as_ [private] |
Definition at line 102 of file cob_sdh.cpp.
std::vector<int> SdhNode::axes_ [private] |
Definition at line 134 of file cob_sdh.cpp.
int SdhNode::baudrate_ [private] |
Definition at line 123 of file cob_sdh.cpp.
int SdhNode::DOF_ [private] |
Definition at line 128 of file cob_sdh.cpp.
SDH::cDSA* SdhNode::dsa_ [private] |
Definition at line 115 of file cob_sdh.cpp.
int SdhNode::dsadevicenum_ [private] |
Definition at line 122 of file cob_sdh.cpp.
std::string SdhNode::dsadevicestring_ [private] |
Definition at line 121 of file cob_sdh.cpp.
bool SdhNode::hasNewGoal_ [private] |
Definition at line 136 of file cob_sdh.cpp.
int SdhNode::id_read_ [private] |
Definition at line 123 of file cob_sdh.cpp.
int SdhNode::id_write_ [private] |
Definition at line 123 of file cob_sdh.cpp.
bool SdhNode::isDSAInitialized_ [private] |
Definition at line 127 of file cob_sdh.cpp.
bool SdhNode::isInitialized_ [private] |
Definition at line 126 of file cob_sdh.cpp.
std::vector<std::string> SdhNode::JointNames_ [private] |
Definition at line 133 of file cob_sdh.cpp.
ros::NodeHandle SdhNode::nh_ |
create a handle for this node, initialize node
Definition at line 88 of file cob_sdh.cpp.
double SdhNode::pi_ [private] |
Definition at line 129 of file cob_sdh.cpp.
SDH::cSDH* SdhNode::sdh_ [private] |
Definition at line 114 of file cob_sdh.cpp.
int SdhNode::sdhdevicenum_ [private] |
Definition at line 120 of file cob_sdh.cpp.
std::string SdhNode::sdhdevicestring_ [private] |
Definition at line 119 of file cob_sdh.cpp.
std::string SdhNode::sdhdevicetype_ [private] |
Definition at line 118 of file cob_sdh.cpp.
ros::ServiceServer SdhNode::srvServer_Init_ [private] |
Definition at line 96 of file cob_sdh.cpp.
ros::ServiceServer SdhNode::srvServer_Recover_ [private] |
Definition at line 98 of file cob_sdh.cpp.
ros::ServiceServer SdhNode::srvServer_SetOperationMode_ [private] |
Definition at line 99 of file cob_sdh.cpp.
ros::ServiceServer SdhNode::srvServer_Stop_ [private] |
Definition at line 97 of file cob_sdh.cpp.
std::vector<SDH::cSDH::eAxisState> SdhNode::state_ [private] |
Definition at line 116 of file cob_sdh.cpp.
std::vector<double> SdhNode::targetAngles_ [private] |
Definition at line 135 of file cob_sdh.cpp.
double SdhNode::timeout_ [private] |
Definition at line 124 of file cob_sdh.cpp.
ros::Publisher SdhNode::topicPub_ControllerState_ [private] |
Definition at line 92 of file cob_sdh.cpp.
ros::Publisher SdhNode::topicPub_JointState_ [private] |
Definition at line 91 of file cob_sdh.cpp.
ros::Publisher SdhNode::topicPub_TactileSensor_ [private] |
Definition at line 93 of file cob_sdh.cpp.
trajectory_msgs::JointTrajectory SdhNode::traj_ [private] |
Definition at line 131 of file cob_sdh.cpp.
diagnostic_updater::Updater SdhNode::updater_ [private] |
Definition at line 111 of file cob_sdh.cpp.