humotion / examples / meka / src / mekajointinterface.cpp @ 196b8635
History | View | Annotate | Download (7.57 KB)
1 |
#include "mekajointinterface.h" |
---|---|
2 |
using namespace std; |
3 |
|
4 |
//WARNING: DO NOT CHANGE THIS; VELOCITYMODE IS NOT YET IMPLEMENTED
|
5 |
#define POSITION_CONTROL 1 |
6 |
|
7 |
void MekaJointInterface::incoming_controlstate(const m3meka_msgs::M3ControlStates &control_state){ |
8 |
//incoming controller status
|
9 |
for (unsigned int i = 0; i<control_state.group_name.size(); i++){ |
10 |
if (control_state.group_name[i] == "head"){ |
11 |
//enable/disable based on controller status
|
12 |
if (control_state.state[i] == m3meka_msgs::M3ControlStates::START){
|
13 |
//controller up and running
|
14 |
if (!controller_enabled){
|
15 |
printf("> incoming control state (%d), enabling jointstate output\n",control_state.state[i]);
|
16 |
controller_enabled = true;
|
17 |
} |
18 |
}else{
|
19 |
//controller in estop/stopped etc
|
20 |
if (controller_enabled){
|
21 |
printf("> incoming control state (%d), DISABLING jointstate output\n",control_state.state[i]);
|
22 |
controller_enabled = false;
|
23 |
} |
24 |
} |
25 |
} |
26 |
} |
27 |
} |
28 |
|
29 |
void MekaJointInterface::incoming_jointstates(const sensor_msgs::JointState & msg){ |
30 |
//fetch current timestamp
|
31 |
double timestamp = msg.header.stamp.toSec();
|
32 |
|
33 |
//iterate through incoming joints and filter out joints we need:
|
34 |
for(int i=0; i<msg.name.size(); i++){ |
35 |
|
36 |
string name = msg.name[i];
|
37 |
//printf("incoming data for joint '%s'\n", name.c_str());
|
38 |
|
39 |
int id = -1; |
40 |
if (name == "head_j1"){ |
41 |
id = ID_NECK_PAN; |
42 |
}else if(name == "head_j0"){ |
43 |
id = ID_NECK_TILT; |
44 |
} |
45 |
|
46 |
//store data:
|
47 |
if (id != -1){ |
48 |
//printf("> storing joint data for joint id %d\n", id);
|
49 |
if (i >= msg.position.size()){
|
50 |
printf("> joint state msg is missing position data for joint '%s'...\n", name.c_str());
|
51 |
return;
|
52 |
} |
53 |
if (i >= msg.velocity.size()){
|
54 |
//printf("> joint state msg is missing velocity data for joint '%s'...\n", name.c_str());
|
55 |
//exit(EXIT_FAILURE);
|
56 |
return;
|
57 |
} |
58 |
//ok, safe to access data
|
59 |
if (id == ID_NECK_PAN){
|
60 |
//joint is inverted
|
61 |
JointInterface::store_incoming_position(id, -180.0 / M_PI * msg.position[i], timestamp); |
62 |
JointInterface::store_incoming_speed( id, -180.0 / M_PI * msg.velocity[i], timestamp); |
63 |
}else if (id == ID_NECK_TILT){ |
64 |
JointInterface::store_incoming_position(id, 180.0 / M_PI * msg.position[i], timestamp); |
65 |
JointInterface::store_incoming_speed( id, 180.0 / M_PI * msg.velocity[i], timestamp); |
66 |
} |
67 |
} |
68 |
} |
69 |
|
70 |
//dummy data uses current time
|
71 |
timestamp = get_timestamp_s(); |
72 |
|
73 |
//store dummy positions for joints we do not know about:
|
74 |
store_dummy_data(ID_LIP_LEFT_UPPER, timestamp); |
75 |
store_dummy_data(ID_LIP_LEFT_LOWER, timestamp); |
76 |
store_dummy_data(ID_LIP_CENTER_UPPER, timestamp); |
77 |
store_dummy_data(ID_LIP_CENTER_LOWER, timestamp); |
78 |
store_dummy_data(ID_LIP_RIGHT_UPPER, timestamp); |
79 |
store_dummy_data(ID_LIP_RIGHT_LOWER, timestamp); |
80 |
|
81 |
store_dummy_data(ID_NECK_ROLL, timestamp); |
82 |
store_dummy_data(ID_EYES_BOTH_UD, timestamp); |
83 |
store_dummy_data(ID_EYES_LEFT_LR, timestamp); |
84 |
store_dummy_data(ID_EYES_RIGHT_LR, timestamp); |
85 |
store_dummy_data(ID_EYES_LEFT_LID_LOWER, timestamp); |
86 |
store_dummy_data(ID_EYES_LEFT_LID_UPPER, timestamp); |
87 |
store_dummy_data(ID_EYES_LEFT_BROW, timestamp); |
88 |
store_dummy_data(ID_EYES_RIGHT_LID_LOWER, timestamp); |
89 |
store_dummy_data(ID_EYES_RIGHT_LID_UPPER, timestamp); |
90 |
store_dummy_data(ID_EYES_RIGHT_BROW, timestamp); |
91 |
|
92 |
} |
93 |
|
94 |
void MekaJointInterface::store_dummy_data(int id, double timestamp){ |
95 |
JointInterface::store_incoming_position(id, 0.0, timestamp); |
96 |
JointInterface::store_incoming_speed(id, 0.0, timestamp); |
97 |
} |
98 |
|
99 |
//! constructor
|
100 |
MekaJointInterface::MekaJointInterface(string _input_scope, string control_scope, string _output_scope) : humotion::server::JointInterface(){ |
101 |
input_scope = _input_scope; |
102 |
output_scope = _output_scope; |
103 |
|
104 |
controller_enabled = false;
|
105 |
|
106 |
//subscribe to meka joint states
|
107 |
int argc = 0; |
108 |
ros::init(argc, (char**)NULL, "meka_humotion"); |
109 |
ros::NodeHandle n; |
110 |
|
111 |
printf("> listening on jointstates on '%s'\n",input_scope.c_str());
|
112 |
joint_state_subscriber = n.subscribe(input_scope, 150, &MekaJointInterface::incoming_jointstates, this); |
113 |
|
114 |
printf("> listening on controlstates on '%s'\n",control_scope.c_str());
|
115 |
control_state_subscriber = n.subscribe(control_scope, 150, &MekaJointInterface::incoming_controlstate, this); |
116 |
|
117 |
printf("> sending targets on '%s'\n", output_scope.c_str());
|
118 |
target_publisher = n.advertise<trajectory_msgs::JointTrajectory>(output_scope, 100);
|
119 |
|
120 |
//tell humotion about min/max joint values:
|
121 |
init_joints(); |
122 |
} |
123 |
|
124 |
//! destructor
|
125 |
MekaJointInterface::~MekaJointInterface(){ |
126 |
} |
127 |
|
128 |
|
129 |
|
130 |
void MekaJointInterface::run(){
|
131 |
ros::spin(); |
132 |
} |
133 |
|
134 |
|
135 |
double MekaJointInterface::get_timestamp_s(){
|
136 |
struct timespec spec;
|
137 |
clock_gettime(CLOCK_REALTIME, &spec); |
138 |
return spec.tv_sec + spec.tv_nsec / 1.0e9; |
139 |
} |
140 |
|
141 |
//! set the target position of a joint
|
142 |
//! \param enum id of joint
|
143 |
//! \param float value
|
144 |
void MekaJointInterface::publish_target_position(int e){ |
145 |
//we do this in execute motion for all joints at once...
|
146 |
} |
147 |
|
148 |
|
149 |
//! actually execute the scheduled motion commands
|
150 |
void MekaJointInterface::execute_motion(){
|
151 |
if (controller_enabled){
|
152 |
//build msg
|
153 |
trajectory_msgs::JointTrajectory msg; |
154 |
msg.joint_names.push_back("head_j0");
|
155 |
msg.joint_names.push_back("head_j1");
|
156 |
|
157 |
trajectory_msgs::JointTrajectoryPoint p; |
158 |
p.positions.push_back(joint_target[ID_NECK_TILT] * M_PI / 180.0); |
159 |
//pan joint is inverted!
|
160 |
p.positions.push_back(-joint_target[ID_NECK_PAN] * M_PI / 180.0); |
161 |
//printf("targets pan=%4.1f tilt=%4.1f (eye p %4.1f t %4.2f)\n",joint_target[ID_NECK_TILT],joint_target[ID_NECK_PAN],joint_target[ID_EYES_LEFT_LR],joint_target[ID_EYES_BOTH_UD]);
|
162 |
|
163 |
p.time_from_start = ros::Duration(1.2 * 1.0 / humotion::server::Server::MOTION_UPDATERATE); |
164 |
|
165 |
msg.points.push_back(p); |
166 |
|
167 |
target_publisher.publish(msg); |
168 |
} |
169 |
} |
170 |
|
171 |
|
172 |
//! prepare and enable a joint
|
173 |
//! NOTE: this should also prefill the min/max positions for this joint
|
174 |
//! \param the enum id of a joint
|
175 |
void MekaJointInterface::enable_joint(int e){ |
176 |
//meka does not support this, joints are always enabled
|
177 |
} |
178 |
|
179 |
//! shutdown and disable a joint
|
180 |
//! \param the enum id of a joint
|
181 |
void MekaJointInterface::disable_joint(int e){ |
182 |
//meka does not support this, joints are always enabled
|
183 |
} |
184 |
|
185 |
void MekaJointInterface::store_min_max(int id, float min, float max){ |
186 |
joint_min[id] = min; |
187 |
joint_max[id] = max; |
188 |
} |
189 |
|
190 |
void MekaJointInterface::init_joints(){
|
191 |
store_min_max(ID_NECK_TILT, -37, 1); |
192 |
store_min_max(ID_NECK_PAN, -70, 70); |
193 |
|
194 |
store_min_max(ID_NECK_ROLL, -1, 1); |
195 |
store_min_max(ID_EYES_BOTH_UD, -1, 1); |
196 |
store_min_max(ID_EYES_LEFT_LR, -1, 1); |
197 |
store_min_max(ID_EYES_RIGHT_LR, -1, 1); |
198 |
store_min_max(ID_EYES_LEFT_LID_UPPER, -1, 1); |
199 |
store_min_max(ID_EYES_LEFT_LID_LOWER, -1, 1); |
200 |
store_min_max(ID_EYES_RIGHT_LID_UPPER, -1, 1); |
201 |
store_min_max(ID_EYES_RIGHT_LID_LOWER, -1, 1); |
202 |
store_min_max(ID_EYES_LEFT_BROW, -1, 1); |
203 |
store_min_max(ID_EYES_RIGHT_BROW, -1, 1); |
204 |
store_min_max(ID_LIP_CENTER_UPPER, -1, 1); |
205 |
store_min_max(ID_LIP_CENTER_LOWER, -1, 1); |
206 |
store_min_max(ID_LIP_LEFT_UPPER, -1, 1); |
207 |
store_min_max(ID_LIP_LEFT_LOWER, -1, 1); |
208 |
store_min_max(ID_LIP_RIGHT_UPPER, -1, 1); |
209 |
store_min_max(ID_LIP_RIGHT_LOWER, -1, 1); |
210 |
} |
211 |
|