test_glove.cpp
Go to the documentation of this file.
1 
18 #include "ros/ros.h"
19 #include "asr_msgs/AsrGlove.h"
20 #include "asr_msgs/AsrObject.h"
21 #include <sensor_msgs/JointState.h>
23 
26 sensor_msgs::JointState joint_state;
27 
32 void callback(const asr_msgs::AsrGloveConstPtr& msg)
33 {
34  joint_state.header.stamp = ros::Time::now();
35 
36  // wrist: not needed because used in combination with asr_flock_of_birds
37  joint_state.position[0] = 0;
38  joint_state.position[1] = 0;
39 
40  // some values are manually adjusted since its difficult to calibrate
41  // TODO: correct mapping of thumb joints
42  joint_state.position[2] = 0.17;
43  joint_state.position[3] = 0.02;
44  joint_state.position[4] = 0.17;
45  joint_state.position[5] = msg->data[5];
46 
47  joint_state.position[6] = msg->data[6];
48  joint_state.position[7] = msg->data[7];
49  joint_state.position[8] = msg->data[8];
50  joint_state.position[9] = msg->data[9] * (-1);
51 
52  joint_state.position[10] = msg->data[10] - 0.1;
53  joint_state.position[11] = msg->data[11];
54  joint_state.position[12] = msg->data[12];
55  joint_state.position[13] = msg->data[13] - 0.5;
56 
57  joint_state.position[14] = msg->data[14];
58  joint_state.position[15] = msg->data[15] - 0.15;
59  joint_state.position[16] = msg->data[16];
60  joint_state.position[17] = msg->data[17] - 0.5;
61 
62  joint_state.position[18] = msg->data[18] - 0.3;
63  joint_state.position[19] = msg->data[19] - 0.3;
64  joint_state.position[20] = msg->data[20];
65  joint_state.position[21] = msg->data[21] * (-1) + 0.1;
66 
67  pub_states.publish(joint_state);
68 }
69 
70 int main(int argc, char **argv)
71 {
72  ros::init(argc, argv, "test_glove");
73  ros::NodeHandle node;
74 
75  sub_states = node.subscribe("rightGloveData_radian", 1, callback);
76  pub_states = node.advertise<sensor_msgs::JointState>("joint_states", 1);
77 
78  joint_state.name.resize(22);
79  joint_state.position.resize(22);
80 
81  // the names are set accordingly to the names used in the xml model
82  joint_state.name[0] ="wr_j0";
83  joint_state.name[1] ="wr_j1";
84 
85  joint_state.name[2] ="th_j0";
86  joint_state.name[3] ="th_j1";
87  joint_state.name[4] ="th_j2";
88  joint_state.name[5] ="th_j3";
89 
90  joint_state.name[6] ="in_j1";
91  joint_state.name[7] ="in_j0";
92  joint_state.name[8] ="in_j2";
93  joint_state.name[9] ="in_j3";
94 
95  joint_state.name[10] ="mi_j1";
96  joint_state.name[11] ="mi_j0";
97  joint_state.name[12] ="mi_j2";
98  joint_state.name[13] ="mi_j3";
99 
100  joint_state.name[14] ="ri_j1";
101  joint_state.name[15] ="ri_j0";
102  joint_state.name[16] ="ri_j2";
103  joint_state.name[17] ="ri_j3";
104 
105  joint_state.name[18] ="pi_j1";
106  joint_state.name[19] ="pi_j0";
107  joint_state.name[20] ="pi_j2";
108  joint_state.name[21] ="pi_j3";
109 
110  ros::spin();
111 
112  return 0;
113 }
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
Definition: test_glove.cpp:70
ROSCPP_DECL void spin(Spinner &spinner)
ros::Subscriber sub_states
Definition: test_glove.cpp:24
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void callback(const asr_msgs::AsrGloveConstPtr &msg)
Definition: test_glove.cpp:32
static Time now()
ros::Publisher pub_states
Definition: test_glove.cpp:25
sensor_msgs::JointState joint_state
Definition: test_glove.cpp:26


asr_cyberglove_visualization
Author(s): Heller Florian, Jäkel Rainer, Kasper Alexander, Meißner Pascal, Nguyen Trung, Yi Xie
autogenerated on Mon Jun 10 2019 12:43:22