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 "std_msgs/Float32.h"
#include <stdio.h>
#include <math.h>
#include <string>
#include "controlAllegroHand.h"
Include dependency graph for allegroNode.cpp:

Go to the source code of this file.

Defines

#define DEGREES_TO_RADIANS(angle)   ((angle) / 180.0 * M_PI)
#define EXT_CMD_TOPIC   "/allegroHand/external_cmd"
#define JOINT_CMD_TOPIC   "/allegroHand/joint_cmd"
#define JOINT_STATE_TOPIC   "/allegroHand/joint_states"
#define RADIANS_TO_DEGREES(radians)   ((radians) * (180.0 / M_PI))

Functions

void extCmdCallback (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}
std::string dGainParams [DOF_JOINTS]
double dt
std::string ext_cmd
ros::Subscriber external_cmd_sub
int frame = 0
double home_pose [DOF_JOINTS]
std::string initialPosition [DOF_JOINTS]
ros::Subscriber joint_cmd_sub
ros::Publisher joint_state_pub
std::string jointNames [DOF_JOINTS]
double k_d [DOF_JOINTS]
double k_p [DOF_JOINTS]
int lEmergencyStop = 0
sensor_msgs::JointState msgJoint
boost::mutexmutex
std::string pGainParams [DOF_JOINTS]
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 DEGREES_TO_RADIANS (   angle)    ((angle) / 180.0 * M_PI)

Definition at line 32 of file allegroNode.cpp.

#define EXT_CMD_TOPIC   "/allegroHand/external_cmd"

Definition at line 38 of file allegroNode.cpp.

#define JOINT_CMD_TOPIC   "/allegroHand/joint_cmd"

Definition at line 37 of file allegroNode.cpp.

#define JOINT_STATE_TOPIC   "/allegroHand/joint_states"

Definition at line 36 of file allegroNode.cpp.

#define RADIANS_TO_DEGREES (   radians)    ((radians) * (180.0 / M_PI))

Definition at line 31 of file allegroNode.cpp.


Function Documentation

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

Definition at line 131 of file allegroNode.cpp.

int main ( int  argc,
char **  argv 
)

Definition at line 240 of file allegroNode.cpp.

void SetjointCallback ( const sensor_msgs::JointState &  msg)

Definition at line 122 of file allegroNode.cpp.

void timerCallback ( const ros::TimerEvent event)

Definition at line 153 of file allegroNode.cpp.


Variable Documentation

controlAllegroHand* canDevice

Definition at line 113 of file allegroNode.cpp.

double current_position[DOF_JOINTS] = {0.0}

Definition at line 40 of file allegroNode.cpp.

Definition at line 43 of file allegroNode.cpp.

double current_velocity[DOF_JOINTS] = {0.0}

Definition at line 46 of file allegroNode.cpp.

Definition at line 48 of file allegroNode.cpp.

double desired_position[DOF_JOINTS] = {0.0}

Definition at line 50 of file allegroNode.cpp.

double desired_torque[DOF_JOINTS] = {0.0}

Definition at line 51 of file allegroNode.cpp.

std::string dGainParams[DOF_JOINTS]
Initial value:
 {      "~gains_pd/d/j00", "~gains_pd/d/j01", "~gains_pd/d/j02", "~gains_pd/d/j03", 
                                                                                "~gains_pd/d/j10", "~gains_pd/d/j11", "~gains_pd/d/j12", "~gains_pd/d/j13",
                                                                                "~gains_pd/d/j20", "~gains_pd/d/j21", "~gains_pd/d/j22", "~gains_pd/d/j23", 
                                                                                "~gains_pd/d/j30", "~gains_pd/d/j31", "~gains_pd/d/j32", "~gains_pd/d/j33"}

Definition at line 75 of file allegroNode.cpp.

double dt

Definition at line 110 of file allegroNode.cpp.

std::string ext_cmd

Definition at line 104 of file allegroNode.cpp.

Definition at line 102 of file allegroNode.cpp.

int frame = 0

Definition at line 92 of file allegroNode.cpp.

Initial value:
 {   0.0,  -10.0,   45.0,   45.0,  
                                                                                  0.0,  -10.0,   45.0,   45.0,  
                                                                                  5.0,   -5.0,   50.0,   45.0,  
                                                                             60.0,   25.0,   15.0,   45.0 }

Definition at line 64 of file allegroNode.cpp.

Initial value:
 {      "~initial_position/j00", "~initial_position/j01", "~initial_position/j02", "~initial_position/j03", 
                                                                                        "~initial_position/j10", "~initial_position/j11", "~initial_position/j12", "~initial_position/j13",
                                                                                        "~initial_position/j20", "~initial_position/j21", "~initial_position/j22", "~initial_position/j23", 
                                                                                        "~initial_position/j30", "~initial_position/j31", "~initial_position/j32", "~initial_position/j33"}

Definition at line 80 of file allegroNode.cpp.

Definition at line 101 of file allegroNode.cpp.

Definition at line 100 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 86 of file allegroNode.cpp.

double k_d[DOF_JOINTS]
Initial value:
 {  15.0,   20.0,   15.0,   15.0,  
                                                                                 15.0,   20.0,   15.0,   15.0,  
                                                                                 15.0,   20.0,   15.0,   15.0,
                                                                                 30.0,   20.0,   20.0,   15.0 }

Definition at line 58 of file allegroNode.cpp.

double k_p[DOF_JOINTS]
Initial value:
 { 600.0,  600.0,  600.0, 1000.0,  
                                                                                600.0,  600.0,  600.0, 1000.0,  
                                                                                600.0,  600.0,  600.0, 1000.0,
                                                                           1000.0, 1000.0, 1000.0,  600.0 }

Definition at line 53 of file allegroNode.cpp.

int lEmergencyStop = 0

Definition at line 95 of file allegroNode.cpp.

sensor_msgs::JointState msgJoint

Definition at line 103 of file allegroNode.cpp.

Definition at line 97 of file allegroNode.cpp.

std::string pGainParams[DOF_JOINTS]
Initial value:
 {      "~gains_pd/p/j00", "~gains_pd/p/j01", "~gains_pd/p/j02", "~gains_pd/p/j03", 
                                                                                "~gains_pd/p/j10", "~gains_pd/p/j11", "~gains_pd/p/j12", "~gains_pd/p/j13",
                                                                                "~gains_pd/p/j20", "~gains_pd/p/j21", "~gains_pd/p/j22", "~gains_pd/p/j23", 
                                                                                "~gains_pd/p/j30", "~gains_pd/p/j31", "~gains_pd/p/j32", "~gains_pd/p/j33"}

Definition at line 70 of file allegroNode.cpp.

double previous_position[DOF_JOINTS] = {0.0}

Definition at line 41 of file allegroNode.cpp.

Definition at line 44 of file allegroNode.cpp.

double previous_velocity[DOF_JOINTS] = {0.0}

Definition at line 47 of file allegroNode.cpp.

double secs

Definition at line 109 of file allegroNode.cpp.

Definition at line 108 of file allegroNode.cpp.

Definition at line 107 of file allegroNode.cpp.



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