Typedefs | Functions | Variables
cob_hand_node.cpp File Reference
#include <cob_hand_bridge/InitFinger.h>
#include <cob_hand_bridge/Status.h>
#include <std_srvs/Trigger.h>
#include <sensor_msgs/JointState.h>
#include <control_msgs/FollowJointTrajectoryAction.h>
#include <diagnostic_updater/publisher.h>
#include <actionlib/server/simple_action_server.h>
#include <ros/ros.h>
#include <boost/thread/mutex.hpp>
#include <boost/shared_ptr.hpp>
#include <boost/scoped_ptr.hpp>
#include <angles/angles.h>
#include <gpio.h>
#include <sdhx.h>
Include dependency graph for cob_hand_node.cpp:

Go to the source code of this file.

Typedefs

typedef
actionlib::SimpleActionServer
< control_msgs::FollowJointTrajectoryAction > 
FollowJointTrajectoryActionServer

Functions

void cancelCB ()
bool checkAction_nolock (bool deadline_exceeded)
void goalCB ()
bool halt ()
bool haltCallback (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
void handleDeadline (const ros::TimerEvent &)
bool init ()
bool initCallback (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
bool isFingerReady_nolock ()
int main (int argc, char *argv[])
bool recover ()
bool recoverCallback (std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
void reportDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat)
void resendCommand (const ros::TimerEvent &e)
void statusCallback (const ros::TimerEvent &e)

Variables

boost::scoped_ptr
< FollowJointTrajectoryActionServer
g_as
cob_hand_bridge::JointValues g_command
ros::Timer g_command_timer
bool g_control_stopped
ros::Timer g_deadline_timer
cob_hand_bridge::JointValues g_default_command
control_msgs::FollowJointTrajectoryGoalConstPtr g_goal
std::vector< double > g_goal_tolerance
ros::ServiceServer g_halt_srv
ros::ServiceServer g_init_srv
bool g_initialized
sensor_msgs::JointState g_js
ros::Publisher g_js_pub
bool g_motion_stopped
bool g_motors_moved
boost::mutex g_mutex
std::string g_port
ros::ServiceServer g_recover_srv
boost::scoped_ptr< SDHXg_sdhx
boost::shared_ptr
< cob_hand_bridge::Status
g_status
double g_stopped_current
double g_stopped_velocity
boost::shared_ptr
< diagnostic_updater::TimeStampStatus
g_topic_status

Typedef Documentation

typedef actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction> FollowJointTrajectoryActionServer

Definition at line 53 of file cob_hand_node.cpp.


Function Documentation

void cancelCB ( )

Definition at line 396 of file cob_hand_node.cpp.

bool checkAction_nolock ( bool  deadline_exceeded)

Definition at line 76 of file cob_hand_node.cpp.

void goalCB ( )

Definition at line 300 of file cob_hand_node.cpp.

bool halt ( )

Definition at line 106 of file cob_hand_node.cpp.

Definition at line 184 of file cob_hand_node.cpp.

void handleDeadline ( const ros::TimerEvent )

Definition at line 288 of file cob_hand_node.cpp.

bool init ( )

Definition at line 115 of file cob_hand_node.cpp.

Definition at line 152 of file cob_hand_node.cpp.

Definition at line 72 of file cob_hand_node.cpp.

int main ( int  argc,
char *  argv[] 
)

Definition at line 427 of file cob_hand_node.cpp.

bool recover ( )

Definition at line 134 of file cob_hand_node.cpp.

Definition at line 195 of file cob_hand_node.cpp.

Definition at line 263 of file cob_hand_node.cpp.

void resendCommand ( const ros::TimerEvent e)

Definition at line 406 of file cob_hand_node.cpp.

void statusCallback ( const ros::TimerEvent e)

Definition at line 206 of file cob_hand_node.cpp.


Variable Documentation

Definition at line 54 of file cob_hand_node.cpp.

Definition at line 56 of file cob_hand_node.cpp.

Definition at line 58 of file cob_hand_node.cpp.

Definition at line 64 of file cob_hand_node.cpp.

Definition at line 59 of file cob_hand_node.cpp.

Definition at line 57 of file cob_hand_node.cpp.

control_msgs::FollowJointTrajectoryGoalConstPtr g_goal

Definition at line 55 of file cob_hand_node.cpp.

std::vector<double> g_goal_tolerance

Definition at line 66 of file cob_hand_node.cpp.

Definition at line 50 of file cob_hand_node.cpp.

Definition at line 49 of file cob_hand_node.cpp.

Definition at line 62 of file cob_hand_node.cpp.

sensor_msgs::JointState g_js

Definition at line 47 of file cob_hand_node.cpp.

Definition at line 46 of file cob_hand_node.cpp.

Definition at line 63 of file cob_hand_node.cpp.

Definition at line 65 of file cob_hand_node.cpp.

boost::mutex g_mutex

Definition at line 41 of file cob_hand_node.cpp.

std::string g_port

Definition at line 67 of file cob_hand_node.cpp.

Definition at line 51 of file cob_hand_node.cpp.

boost::scoped_ptr<SDHX> g_sdhx

Definition at line 70 of file cob_hand_node.cpp.

boost::shared_ptr<cob_hand_bridge::Status> g_status

Definition at line 43 of file cob_hand_node.cpp.

Definition at line 61 of file cob_hand_node.cpp.

Definition at line 60 of file cob_hand_node.cpp.

Definition at line 44 of file cob_hand_node.cpp.



cob_hand_bridge
Author(s): Mathias Lüdtke
autogenerated on Thu Jun 6 2019 20:43:57