#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 <algorithm>
#include <string>
#include "controlAllegroHand.h"
Go to the source code of this file.
#define DEGREES_TO_RADIANS | ( | angle | ) | ((angle) / 180.0 * M_PI) |
Definition at line 38 of file allegroNode.cpp.
#define EXT_CMD_TOPIC "/allegroHand/external_cmd" |
Definition at line 44 of file allegroNode.cpp.
#define JOINT_CMD_TOPIC "/allegroHand/joint_cmd" |
Definition at line 43 of file allegroNode.cpp.
#define JOINT_CURRENT_TOPIC "/allegroHand/joint_current_states" |
Definition at line 47 of file allegroNode.cpp.
#define JOINT_DESIRED_TOPIC "/allegroHand/joint_desired_states" |
Definition at line 46 of file allegroNode.cpp.
#define JOINT_STATE_TOPIC "/allegroHand/joint_states" |
Definition at line 42 of file allegroNode.cpp.
#define RADIANS_TO_DEGREES | ( | radians | ) | ((radians) * (180.0 / M_PI)) |
Definition at line 37 of file allegroNode.cpp.
void extCmdCallback | ( | const std_msgs::String::ConstPtr & | msg | ) |
Definition at line 163 of file allegroNode.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 309 of file allegroNode.cpp.
void SetjointCallback | ( | const sensor_msgs::JointState & | msg | ) |
Definition at line 154 of file allegroNode.cpp.
void timerCallback | ( | const ros::TimerEvent & | event | ) |
Definition at line 186 of file allegroNode.cpp.
controlAllegroHand* canDevice |
Definition at line 145 of file allegroNode.cpp.
double current_position[DOF_JOINTS] = {0.0} |
Definition at line 51 of file allegroNode.cpp.
double current_position_filtered[DOF_JOINTS] = {0.0} |
Definition at line 53 of file allegroNode.cpp.
double current_velocity[DOF_JOINTS] = {0.0} |
Definition at line 57 of file allegroNode.cpp.
double current_velocity_filtered[DOF_JOINTS] = {0.0} |
Definition at line 59 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 61 of file allegroNode.cpp.
double desired_velocity[DOF_JOINTS] = {0.0} |
Definition at line 56 of file allegroNode.cpp.
std::string dGainParams[DOF_JOINTS] |
{ "~gains_velSat/d/j00", "~gains_velSat/d/j01", "~gains_velSat/d/j02", "~gains_velSat/d/j03", "~gains_velSat/d/j10", "~gains_velSat/d/j11", "~gains_velSat/d/j12", "~gains_velSat/d/j13", "~gains_velSat/d/j20", "~gains_velSat/d/j21", "~gains_velSat/d/j22", "~gains_velSat/d/j23", "~gains_velSat/d/j30", "~gains_velSat/d/j31", "~gains_velSat/d/j32", "~gains_velSat/d/j33"}
Definition at line 95 of file allegroNode.cpp.
double dt |
Definition at line 142 of file allegroNode.cpp.
std::string ext_cmd |
Definition at line 135 of file allegroNode.cpp.
Definition at line 131 of file allegroNode.cpp.
int frame = 0 |
Definition at line 118 of file allegroNode.cpp.
double home_pose[DOF_JOINTS] |
{ 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 84 of file allegroNode.cpp.
std::string initialPosition[DOF_JOINTS] |
{ "~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 105 of file allegroNode.cpp.
Definition at line 130 of file allegroNode.cpp.
Definition at line 128 of file allegroNode.cpp.
Definition at line 127 of file allegroNode.cpp.
Definition at line 126 of file allegroNode.cpp.
std::string jointNames[DOF_JOINTS] |
{ "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 111 of file allegroNode.cpp.
double k_d[DOF_JOINTS] |
{ 140.0, 140.0, 140.0, 140.0, 140.0, 140.0, 140.0, 140.0, 140.0, 140.0, 140.0, 140.0, 140.0, 140.0, 140.0, 140.0 }
Definition at line 72 of file allegroNode.cpp.
double k_p[DOF_JOINTS] |
{ 1200.0, 1200.0, 1200.0, 1200.0, 1200.0, 1200.0, 1200.0, 1200.0, 1200.0, 1200.0, 1200.0, 1200.0, 1200.0, 1200.0, 1200.0, 1200.0 }
Definition at line 67 of file allegroNode.cpp.
int lEmergencyStop = 0 |
Definition at line 121 of file allegroNode.cpp.
sensor_msgs::JointState msgJoint |
Definition at line 134 of file allegroNode.cpp.
sensor_msgs::JointState msgJoint_current |
Definition at line 133 of file allegroNode.cpp.
sensor_msgs::JointState msgJoint_desired |
Definition at line 132 of file allegroNode.cpp.
Definition at line 123 of file allegroNode.cpp.
std::string pGainParams[DOF_JOINTS] |
{ "~gains_velSat/p/j00", "~gains_velSat/p/j01", "~gains_velSat/p/j02", "~gains_velSat/p/j03", "~gains_velSat/p/j10", "~gains_velSat/p/j11", "~gains_velSat/p/j12", "~gains_velSat/p/j13", "~gains_velSat/p/j20", "~gains_velSat/p/j21", "~gains_velSat/p/j22", "~gains_velSat/p/j23", "~gains_velSat/p/j30", "~gains_velSat/p/j31", "~gains_velSat/p/j32", "~gains_velSat/p/j33"}
Definition at line 90 of file allegroNode.cpp.
double previous_position[DOF_JOINTS] = {0.0} |
Definition at line 52 of file allegroNode.cpp.
double previous_position_filtered[DOF_JOINTS] = {0.0} |
Definition at line 54 of file allegroNode.cpp.
double previous_velocity[DOF_JOINTS] = {0.0} |
Definition at line 58 of file allegroNode.cpp.
double secs |
Definition at line 141 of file allegroNode.cpp.
Definition at line 139 of file allegroNode.cpp.
Definition at line 138 of file allegroNode.cpp.
double v[DOF_JOINTS] = {0.0} |
Definition at line 64 of file allegroNode.cpp.
double v_max[DOF_JOINTS] |
{ 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0 }
Definition at line 78 of file allegroNode.cpp.
std::string vMaxParams[DOF_JOINTS] |
{ "~gains_velSat/v_max/j00", "~gains_velSat/v_max/j01", "~gains_velSat/v_max/j02", "~gains_velSat/v_max/j03", "~gains_velSat/v_max/j10", "~gains_velSat/v_max/j11", "~gains_velSat/v_max/j12", "~gains_velSat/v_max/j13", "~gains_velSat/v_max/j20", "~gains_velSat/v_max/j21", "~gains_velSat/v_max/j22", "~gains_velSat/v_max/j23", "~gains_velSat/v_max/j30", "~gains_velSat/v_max/j31", "~gains_velSat/v_max/j32", "~gains_velSat/v_max/j33"}
Definition at line 100 of file allegroNode.cpp.