wam_dmp_tracker_driver_node.cpp 7.87 KB
Newer Older
Víctor Silos Sánchez's avatar
Víctor Silos Sánchez committed
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
#include "wam_dmp_tracker_driver_node.h"

WamDmpTrackerDriverNode::WamDmpTrackerDriverNode(ros::NodeHandle &nh) : 
  iri_base_driver::IriBaseNodeDriver<WamDmpTrackerDriver>(nh),
  //  DMPTracker_client_("/estirabot/estirabot_controller/dmp_joint_tracker", true)
  //DMPTracker_client_("/iri_wam/iri_wam_controller/dmp_joint_tracker", true)
  DMPTracker_client_(this->public_node_handle_, "dmp_compliant_joint_tracker", true)
{
  //init class attributes if necessary
  this->loop_rate_ = 50;//in [Hz]

  // [init publishers]
  this->DMPTrackerNewGoal_publisher_ = this->public_node_handle_.advertise<trajectory_msgs::JointTrajectoryPoint>("DMPTracker_output", 1);

  // [init subscribers]
  this->pose_surface_subscriber_ = this->public_node_handle_.subscribe("pose_surface", 10, &WamDmpTrackerDriverNode::pose_surface_callback, this);

  // [init services]

  // [init clients]
  this->wamik_client_ = this->public_node_handle_.serviceClient<iri_common_drivers_msgs::QueryInverseKinematics>("DMP_ik");

  // [init action servers]

  // [init action clients]

  //Init the tracker and the robot  
  //send a goal to the action 
  //   rostopic pub /pose_surface geometry_msgs/PoseStamped "{header: {stamp:ow, frame_id: "camera_depth_optical_frame"},pose: {position: {x: 0, y: -0.35, z: 0.49}, orientation: {x: -0.374, y: -0.374, z: -0.54, w: 0.65}}}" 
  //DMPTracker_goal_.data = my_desired_goal;

  float ifloats[] = {0.0, 1.0, 0.0, 1.8, 0.0, 0.0, 0.0};
  float ffloats[] = {0.0, 1.0, 0.0, 2.0, 0.0, 0.0, 0.0};
  std::vector<float> initial_joints_pose (ifloats, ifloats + sizeof(ifloats)/sizeof(float) );
  std::vector<float> final_joints_pose (ffloats, ffloats + sizeof(ffloats)/sizeof(float) );
  this->private_node_handle_.getParam("initial_joints_pose", initial_joints_pose);
  this->private_node_handle_.getParam("final_joints_pose", final_joints_pose);

  DMPTracker_goal_.initial.positions.resize(7);
  DMPTracker_goal_.initial.positions[0] = initial_joints_pose[0]; 
  DMPTracker_goal_.initial.positions[1] = initial_joints_pose[1];
  DMPTracker_goal_.initial.positions[2] = initial_joints_pose[2];
  DMPTracker_goal_.initial.positions[3] = initial_joints_pose[3];
  DMPTracker_goal_.initial.positions[4] = initial_joints_pose[4];
  DMPTracker_goal_.initial.positions[5] = initial_joints_pose[5];
  DMPTracker_goal_.initial.positions[6] = initial_joints_pose[6];

  DMPTracker_goal_.goal.positions.resize(7); 
  DMPTracker_goal_.goal.positions[0] = final_joints_pose[0]; 
  DMPTracker_goal_.goal.positions[1] = final_joints_pose[1];
  DMPTracker_goal_.goal.positions[2] = final_joints_pose[2];
  DMPTracker_goal_.goal.positions[3] = final_joints_pose[3];
  DMPTracker_goal_.goal.positions[4] = final_joints_pose[4];
  DMPTracker_goal_.goal.positions[5] = final_joints_pose[5];
  DMPTracker_goal_.goal.positions[6] = final_joints_pose[6];

  DMPTrackerMakeActionRequest();

}

void WamDmpTrackerDriverNode::mainNodeThread(void)
{
  //lock access to driver if necessary
  //this->driver_.lock();

  // [fill msg Header if necessary]
  //<publisher_name>.header.stamp = ros::Time::now();
  //<publisher_name>.header.frame_id = "<publisher_topic_name>";

  // [fill msg structures]
  //this->JointTrajectoryPoint_msg_.data = my_var;

  // [fill srv structure and make request to the server]


  // [fill action structure and make request to the action server]
  // DMPTrackerMakeActionRequest();

  // [publish messages]

  //unlock access to driver if previously blocked
  //this->driver_.unlock();
}

/*  [subscriber callbacks] */
void WamDmpTrackerDriverNode::pose_surface_callback(const geometry_msgs::PoseStamped::ConstPtr& msg) 
{ 
  ROS_DEBUG("WamDmpTrackerDriverNode::pose_surface_callback: New Message Received"); 

  //use appropiate mutex to shared variables if necessary 
  //this->driver_.lock(); 
  //this->pose_surface_mutex_.enter(); 

  /* get joints pose from ik */

  wamik_srv_.request.pose.header.frame_id = msg->header.frame_id;
  wamik_srv_.request.pose.pose = msg->pose;
  ROS_DEBUG("WamDmpTrackerDriverNode:: Request: [%d:%d] %f %f %f %f %f %f %f", 
      wamik_srv_.request.pose.header.stamp.sec,
      wamik_srv_.request.pose.header.stamp.nsec,
      wamik_srv_.request.pose.pose.position.x,
      wamik_srv_.request.pose.pose.position.y,
      wamik_srv_.request.pose.pose.position.z,
      wamik_srv_.request.pose.pose.orientation.x,
      wamik_srv_.request.pose.pose.orientation.y,
      wamik_srv_.request.pose.pose.orientation.z,
      wamik_srv_.request.pose.pose.orientation.w
      );

  ROS_DEBUG("WamDmpTrackerDriverNode:: Sending New Request!"); 

  if (wamik_client_.call(wamik_srv_)) 
  { 
    ROS_DEBUG("WamDmpTrackerDriverNode:: Response: %f %f %f %f %f %f %f", 
        wamik_srv_.response.joints.position[0],
        wamik_srv_.response.joints.position[1],
        wamik_srv_.response.joints.position[2],
        wamik_srv_.response.joints.position[3],
        wamik_srv_.response.joints.position[4],
        wamik_srv_.response.joints.position[5],
        wamik_srv_.response.joints.position[6]
        ); 

    trajectory_msgs::JointTrajectoryPoint new_joints;
    new_joints.positions.resize(7);
    for (unsigned int ii=0;ii<7;ii++) {
      new_joints.positions[ii] = wamik_srv_.response.joints.position[ii];
    }

    this->DMPTrackerNewGoal_publisher_.publish(new_joints);

  } 
  else 
  { 
    ROS_ERROR("WamDmpTrackerDriverNode:: Failed to Call Server on topic wamik "); 
  }

  //unlock previously blocked shared variables 
  //this->driver_.unlock(); 
  //this->pose_surface_mutex_.exit(); 
}

/*  [service callbacks] */

/*  [action callbacks] */
void WamDmpTrackerDriverNode::DMPTrackerDone(const actionlib::SimpleClientGoalState& state,  const iri_wam_common_msgs::DMPTrackerResultConstPtr& result) 
{ 
  if( state.toString().compare("SUCCEEDED") == 0 ) {
    ROS_DEBUG("WamDmpTrackerDriverNode::DMPTrackerDone: Goal Achieved!"); 
  } else {
    ROS_DEBUG("WamDmpTrackerDriverNode::DMPTrackerDone: %s", state.toString().c_str()); 
  }
  //copy & work with requested result 
} 

void WamDmpTrackerDriverNode::DMPTrackerActive() 
{ 
  //ROS_DEBUG("WamDmpTrackerDriverNode::DMPTrackerActive: Goal just went active!"); 
} 

void WamDmpTrackerDriverNode::DMPTrackerFeedback(const iri_wam_common_msgs::DMPTrackerFeedbackConstPtr& feedback) 
{ 
  //ROS_DEBUG("WamDmpTrackerDriverNode::DMPTrackerFeedback: Got Feedback!"); 

  bool feedback_is_ok = true; 

  //analyze feedback 
  //my_var = feedback->var; 

  //if feedback is not what expected, cancel requested goal 
  if( !feedback_is_ok ) 
  { 
    DMPTracker_client_.cancelGoal(); 
    ROS_DEBUG("WamDmpTrackerDriverNode::DMPTrackerFeedback: Cancelling Action!"); 
  } 
}

/*  [action requests] */
void WamDmpTrackerDriverNode::DMPTrackerMakeActionRequest() 
{ 
  ROS_DEBUG("WamDmpTrackerDriverNode::DMPTrackerMakeActionRequest: Starting New Request!"); 

  //wait for the action server to start 
  //will wait for infinite time 
  DMPTracker_client_.waitForServer();  
  ROS_DEBUG("WamDmpTrackerDriverNode::DMPTrackerMakeActionRequest: Server is Available!"); 

  DMPTracker_client_.sendGoal(DMPTracker_goal_, 
      boost::bind(&WamDmpTrackerDriverNode::DMPTrackerDone,     this, _1, _2), 
      boost::bind(&WamDmpTrackerDriverNode::DMPTrackerActive,   this), 
      boost::bind(&WamDmpTrackerDriverNode::DMPTrackerFeedback, this, _1)); 

  ROS_DEBUG("WamDmpTrackerDriverNode::DMPTrackerMakeActionRequest: Goal Sent. Wait for Result!"); 

}

void WamDmpTrackerDriverNode::postNodeOpenHook(void)
{
}

void WamDmpTrackerDriverNode::addNodeDiagnostics(void)
{
}

void WamDmpTrackerDriverNode::addNodeOpenedTests(void)
{
}

void WamDmpTrackerDriverNode::addNodeStoppedTests(void)
{
}

void WamDmpTrackerDriverNode::addNodeRunningTests(void)
{
}

void WamDmpTrackerDriverNode::reconfigureNodeHook(int level)
{
}

WamDmpTrackerDriverNode::~WamDmpTrackerDriverNode(void)
{
  // [free dynamic memory]
}

/* main function */
int main(int argc,char *argv[])
{
  return driver_base::main<WamDmpTrackerDriverNode>(argc, argv, "wam_dmp_tracker_driver_node");
}