Defines | Functions | Variables
allegroNode.cpp File Reference
#include <iostream>
#include <boost/thread/thread.hpp>
#include <boost/date_time.hpp>
#include <boost/thread/locks.hpp>
#include "ros/ros.h"
#include "ros/service.h"
#include "ros/service_server.h"
#include "sensor_msgs/JointState.h"
#include "std_msgs/String.h"
#include <stdio.h>
#include <string>
#include "BHand/BHand.h"
#include "controlAllegroHand.h"
Include dependency graph for allegroNode.cpp:

Go to the source code of this file.

Defines

#define JOINT_CMD_TOPIC   "/allegroHand/joint_cmd"
#define JOINT_STATE_TOPIC   "/allegroHand/joint_states"
#define LIB_CMD_TOPIC   "/allegroHand/lib_cmd"

Functions

void libCmdCallback (const std_msgs::String::ConstPtr &msg)
int main (int argc, char **argv)
void SetjointCallback (const sensor_msgs::JointState &msg)
void timerCallback (const ros::TimerEvent &event)

Variables

controlAllegroHand * canDevice
double current_position [DOF_JOINTS] = {0.0}
double current_position_filtered [DOF_JOINTS] = {0.0}
double current_velocity [DOF_JOINTS] = {0.0}
double current_velocity_filtered [DOF_JOINTS] = {0.0}
double desired_position [DOF_JOINTS] = {0.0}
double desired_torque [DOF_JOINTS] = {0.0}
double dt
int frame = 0
eMotionType gMotionType = eMotionType_NONE
ros::Subscriber joint_cmd_sub
ros::Publisher joint_state_pub
std::string jointNames [DOF_JOINTS]
int lEmergencyStop = 0
std::string lib_cmd
ros::Subscriber lib_cmd_sub
bool lIsBegin = false
sensor_msgs::JointState msgJoint
boost::mutexmutex
BHand * pBHand = NULL
bool pdControl = true
double previous_position [DOF_JOINTS] = {0.0}
double previous_position_filtered [DOF_JOINTS] = {0.0}
double previous_velocity [DOF_JOINTS] = {0.0}
double secs
ros::Time tnow
ros::Time tstart

Define Documentation

#define JOINT_CMD_TOPIC   "/allegroHand/joint_cmd"

Definition at line 31 of file allegroNode.cpp.

#define JOINT_STATE_TOPIC   "/allegroHand/joint_states"

Definition at line 30 of file allegroNode.cpp.

#define LIB_CMD_TOPIC   "/allegroHand/lib_cmd"

Definition at line 32 of file allegroNode.cpp.


Function Documentation

void libCmdCallback ( const std_msgs::String::ConstPtr &  msg)

Definition at line 99 of file allegroNode.cpp.

int main ( int  argc,
char **  argv 
)

Definition at line 264 of file allegroNode.cpp.

void SetjointCallback ( const sensor_msgs::JointState &  msg)

Definition at line 87 of file allegroNode.cpp.

void timerCallback ( const ros::TimerEvent event)

Definition at line 158 of file allegroNode.cpp.


Variable Documentation

controlAllegroHand* canDevice

Definition at line 82 of file allegroNode.cpp.

double current_position[DOF_JOINTS] = {0.0}

Definition at line 36 of file allegroNode.cpp.

Definition at line 38 of file allegroNode.cpp.

double current_velocity[DOF_JOINTS] = {0.0}

Definition at line 41 of file allegroNode.cpp.

Definition at line 43 of file allegroNode.cpp.

double desired_position[DOF_JOINTS] = {0.0}

Definition at line 35 of file allegroNode.cpp.

double desired_torque[DOF_JOINTS] = {0.0}

Definition at line 45 of file allegroNode.cpp.

double dt

Definition at line 74 of file allegroNode.cpp.

int frame = 0

Definition at line 55 of file allegroNode.cpp.

eMotionType gMotionType = eMotionType_NONE

Definition at line 77 of file allegroNode.cpp.

Definition at line 66 of file allegroNode.cpp.

Definition at line 65 of file allegroNode.cpp.

std::string jointNames[DOF_JOINTS]
Initial value:
 {    "joint_0.0",    "joint_1.0",    "joint_2.0",   "joint_3.0" , 
                                                                                   "joint_4.0",    "joint_5.0",    "joint_6.0",   "joint_7.0" , 
                                                                                   "joint_8.0",    "joint_9.0",    "joint_10.0",  "joint_11.0", 
                                                                                   "joint_12.0",   "joint_13.0",   "joint_14.0",  "joint_15.0" }

Definition at line 50 of file allegroNode.cpp.

int lEmergencyStop = 0

Definition at line 60 of file allegroNode.cpp.

std::string lib_cmd

Definition at line 47 of file allegroNode.cpp.

Definition at line 67 of file allegroNode.cpp.

bool lIsBegin = false

Definition at line 58 of file allegroNode.cpp.

sensor_msgs::JointState msgJoint

Definition at line 68 of file allegroNode.cpp.

Definition at line 62 of file allegroNode.cpp.

BHand* pBHand = NULL

Definition at line 78 of file allegroNode.cpp.

bool pdControl = true

Definition at line 59 of file allegroNode.cpp.

double previous_position[DOF_JOINTS] = {0.0}

Definition at line 37 of file allegroNode.cpp.

Definition at line 39 of file allegroNode.cpp.

double previous_velocity[DOF_JOINTS] = {0.0}

Definition at line 42 of file allegroNode.cpp.

double secs

Definition at line 73 of file allegroNode.cpp.

Definition at line 72 of file allegroNode.cpp.

Definition at line 71 of file allegroNode.cpp.



allegro_hand_core_grasp
Author(s): Alex Alspach (SimLab), Seungsu Kim (EPFL)
autogenerated on Sun Oct 5 2014 22:09:44