00001 #include "darwin_icra12_alg_node.h"
00002
00003 DarwinIcra12AlgNode::DarwinIcra12AlgNode(void) :
00004 algorithm_base::IriBaseAlgorithm<DarwinIcra12Algorithm>(),
00005 move_right_arm_client_("move_right_arm", true),
00006 move_joints_client_("move_joints", true),
00007 move_base_client_("move_base", true),
00008 move_left_arm_client_("move_left_arm", true),
00009 tf_listener(ros::Duration(10.0))
00010 {
00011
00012 this->loop_rate_ = 1;
00013
00014
00015
00016
00017 this->object_pose_subscriber_ = this->public_node_handle_.subscribe("object_pose", 10, &DarwinIcra12AlgNode::object_pose_callback, this);
00018
00019
00020
00021
00022
00023
00024
00025
00026 sleep(10);
00027 this->arm_moving=false;
00028 this->base_moving=false;
00029 this->joints_moving=false;
00030 this->new_object_pose=false;
00031
00032 this->state=detect_object;
00033 }
00034
00035 DarwinIcra12AlgNode::~DarwinIcra12AlgNode(void)
00036 {
00037
00038 }
00039
00040 void DarwinIcra12AlgNode::mainNodeThread(void)
00041 {
00042 double distance,angle;
00043 int i=0;
00044
00045
00046
00047
00048 ROS_INFO("Thread");
00049
00050
00051
00052
00053 this->object_pose_mutex_.enter();
00054 try{
00055 switch(this->state)
00056 {
00057 case detect_object: if(this->new_object_pose)
00058 {
00059 this->new_object_pose=false;
00060 this->state=make_decision;
00061 }
00062 else
00063 this->state=detect_object;
00064 ROS_INFO("Current state: detect_object");
00065 break;
00066 case make_decision:
00067 distance=sqrt(this->object_pose.pose.position.x*this->object_pose.pose.position.x+
00068 this->object_pose.pose.position.y*this->object_pose.pose.position.y);
00069 angle=atan2(this->object_pose.pose.position.y,this->object_pose.pose.position.x);
00070 if(0)
00071 {
00072 this->state=move_robot;
00073 distance-=0.05;
00074
00075 this->move_base_goal_.target_pose.header=this->object_pose.header;
00076 this->move_base_goal_.target_pose.pose.position.x=distance*cos(angle);
00077 this->move_base_goal_.target_pose.pose.position.y=distance*sin(angle);
00078 this->move_base_goal_.target_pose.pose.position.z=0.0;
00079 this->move_base_goal_.target_pose.pose.orientation=tf::createQuaternionMsgFromYaw(angle);
00080
00081 move_baseMakeActionRequest();
00082 }
00083 else
00084 {
00085 this->move_joints_goal_.trajectory.header.seq=0;
00086 this->move_joints_goal_.trajectory.header.stamp=ros::Time::now();
00087 this->move_joints_goal_.trajectory.header.frame_id="MP_BODY";
00088 this->move_joints_goal_.trajectory.joint_names.resize(2);
00089 this->move_joints_goal_.trajectory.joint_names[0]="j_gripper_l";
00090 this->move_joints_goal_.trajectory.joint_names[1]="j_gripper_r";
00091 this->move_joints_goal_.trajectory.points.resize(1);
00092 this->move_joints_goal_.trajectory.points[0].positions.resize(2);
00093 this->move_joints_goal_.trajectory.points[0].velocities.resize(2);
00094 this->move_joints_goal_.trajectory.points[0].accelerations.resize(2);
00095 this->move_joints_goal_.trajectory.points[0].positions[0]=-30;
00096 this->move_joints_goal_.trajectory.points[0].positions[1]=30;
00097 for(i=0;i<2;i++)
00098 {
00099 this->move_joints_goal_.trajectory.points[0].velocities[i]=60.0;
00100 this->move_joints_goal_.trajectory.points[0].accelerations[i]=100.0;
00101 }
00102 this->move_joints_goal_.trajectory.points[0].time_from_start=ros::Duration(1.0);
00103 move_jointsMakeActionRequest();
00104 this->state=open_gripper;
00105 }
00106 ROS_INFO("Current state: make_decision");
00107 break;
00108 case move_robot: if(this->base_moving)
00109 this->state=move_robot;
00110 else
00111 {
00112 this->move_joints_goal_.trajectory.header.seq=0;
00113 this->move_joints_goal_.trajectory.header.stamp=ros::Time::now();
00114 this->move_joints_goal_.trajectory.header.frame_id="MP_BODY";
00115 this->move_joints_goal_.trajectory.joint_names.resize(2);
00116 this->move_joints_goal_.trajectory.joint_names[0]="j_gripper_l";
00117 this->move_joints_goal_.trajectory.joint_names[1]="j_gripper_r";
00118 this->move_joints_goal_.trajectory.points.resize(1);
00119 this->move_joints_goal_.trajectory.points[0].positions.resize(2);
00120 this->move_joints_goal_.trajectory.points[0].velocities.resize(2);
00121 this->move_joints_goal_.trajectory.points[0].accelerations.resize(2);
00122 this->move_joints_goal_.trajectory.points[0].positions[0]=-30;
00123 this->move_joints_goal_.trajectory.points[0].positions[1]=30;
00124 for(i=0;i<2;i++)
00125 {
00126 this->move_joints_goal_.trajectory.points[0].velocities[i]=60.0;
00127 this->move_joints_goal_.trajectory.points[0].accelerations[i]=100.0;
00128 }
00129 this->move_joints_goal_.trajectory.points[0].time_from_start=ros::Duration(1.0);
00130 move_jointsMakeActionRequest();
00131 this->state=open_gripper;
00132 }
00133 ROS_INFO("Current state: move_robot");
00134 break;
00135 case move_arms: if(this->arm_moving)
00136 this->state=move_arms;
00137 else
00138 {
00139 this->move_joints_goal_.trajectory.header.seq=0;
00140 this->move_joints_goal_.trajectory.header.stamp=ros::Time::now();
00141 this->move_joints_goal_.trajectory.header.frame_id="MP_BODY";
00142 this->move_joints_goal_.trajectory.joint_names.resize(2);
00143 this->move_joints_goal_.trajectory.joint_names[0]="j_gripper_l";
00144 this->move_joints_goal_.trajectory.joint_names[1]="j_gripper_r";
00145 this->move_joints_goal_.trajectory.points.resize(1);
00146 this->move_joints_goal_.trajectory.points[0].positions.resize(2);
00147 this->move_joints_goal_.trajectory.points[0].velocities.resize(2);
00148 this->move_joints_goal_.trajectory.points[0].accelerations.resize(2);
00149 this->move_joints_goal_.trajectory.points[0].positions[0]=30;
00150 this->move_joints_goal_.trajectory.points[0].positions[1]=-30;
00151 for(i=0;i<2;i++)
00152 {
00153 this->move_joints_goal_.trajectory.points[0].velocities[i]=60.0;
00154 this->move_joints_goal_.trajectory.points[0].accelerations[i]=100.0;
00155 }
00156 this->move_joints_goal_.trajectory.points[0].time_from_start=ros::Duration(1.0);
00157 move_jointsMakeActionRequest();
00158 this->state=close_gripper;
00159 }
00160 ROS_INFO("Current state: move_arms");
00161 break;
00162 case open_gripper: if(this->joints_moving)
00163 this->state=open_gripper;
00164 else
00165 {
00166 if(this->new_object_pose)
00167 {
00168 ROS_INFO("Creating goal ... ");
00169 if(this->object_pose.pose.position.y>0)
00170 {
00171 this->move_left_arm_goal_.motion_plan_request.goal_constraints.position_constraints.resize(1);
00172 this->move_left_arm_goal_.motion_plan_request.goal_constraints.position_constraints[0].header.seq=0;
00173 this->move_left_arm_goal_.motion_plan_request.goal_constraints.position_constraints[0].header.stamp=ros::Time::now();
00174 this->move_left_arm_goal_.motion_plan_request.goal_constraints.position_constraints[0].header.frame_id="MP_BODY";
00175 this->move_left_arm_goal_.motion_plan_request.goal_constraints.position_constraints[0].position.x=this->object_pose.pose.position.x;
00176 this->move_left_arm_goal_.motion_plan_request.goal_constraints.position_constraints[0].position.y=this->object_pose.pose.position.y;
00177 this->move_left_arm_goal_.motion_plan_request.goal_constraints.position_constraints[0].position.z=this->object_pose.pose.position.z;
00178 move_left_armMakeActionRequest();
00179 }
00180 else
00181 {
00182 this->move_right_arm_goal_.motion_plan_request.goal_constraints.position_constraints.resize(1);
00183 this->move_right_arm_goal_.motion_plan_request.goal_constraints.position_constraints[0].header.seq=0;
00184 this->move_right_arm_goal_.motion_plan_request.goal_constraints.position_constraints[0].header.stamp=ros::Time::now();
00185 this->move_right_arm_goal_.motion_plan_request.goal_constraints.position_constraints[0].header.frame_id="MP_BODY";
00186 this->move_right_arm_goal_.motion_plan_request.goal_constraints.position_constraints[0].position.x=this->object_pose.pose.position.x;
00187 this->move_right_arm_goal_.motion_plan_request.goal_constraints.position_constraints[0].position.y=this->object_pose.pose.position.y;
00188 this->move_right_arm_goal_.motion_plan_request.goal_constraints.position_constraints[0].position.z=this->object_pose.pose.position.z;
00189 move_right_armMakeActionRequest();
00190 }
00191 this->state=move_arms;
00192 this->new_object_pose=false;
00193 }
00194 else
00195 {
00196 ROS_INFO("waiting new goal ... ");
00197 this->state=open_gripper;
00198 }
00199 }
00200 ROS_INFO("Current state: open_gripper");
00201 break;
00202 case close_gripper: if(this->joints_moving)
00203 this->state=close_gripper;
00204 else
00205 {
00206 this->state=detect_object;
00207 }
00208 ROS_INFO("Current state: close_gripper");
00209 break;
00210 case cancel_motion: this->state=cancel_motion;
00211 ROS_INFO("Current state: cancel_motion");
00212 break;
00213 }
00214 }catch(...){
00215 ROS_INFO("exception!!!!!!!!!!!!!!!!!!!!!1");
00216 }
00217 this->object_pose_mutex_.exit();
00218 }
00219
00220
00221 void DarwinIcra12AlgNode::object_pose_callback(const geometry_msgs::PoseStamped::ConstPtr& msg)
00222 {
00223 bool tf_exists;
00224
00225 ROS_INFO("DarwinIcra12AlgNode::object_pose_callback: New Message Received");
00226
00227
00228
00229 this->object_pose_mutex_.enter();
00230
00231
00232 try{
00233 std::cout << msg->pose.position.x << "," << msg->pose.position.y << "," << msg->pose.position.z << std::endl;
00234
00235 tf_exists = tf_listener.waitForTransform(msg->header.frame_id,std::string("/MP_BODY"),msg->header.stamp,
00236 ros::Duration(10),ros::Duration(0.01));
00237 tf_listener.transformPose(std::string("/MP_BODY"),(*msg),this->object_pose);
00238 std::cout << this->object_pose.pose.position.x << "," << this->object_pose.pose.position.y << "," << this->object_pose.pose.position.z << std::endl;
00239 this->object_pose=(*msg);
00240 this->new_object_pose=true;
00241 }catch(tf::TransformException ex){
00242 ROS_ERROR("NoCollisionAlgNode:: %s",ex.what());
00243 this->new_object_pose=false;
00244 }catch(...){
00245 ROS_INFO("exception!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!11");
00246 }
00247
00248
00249
00250 this->object_pose_mutex_.exit();
00251 }
00252
00253
00254
00255
00256 void DarwinIcra12AlgNode::move_right_armDone(const actionlib::SimpleClientGoalState& state, const arm_navigation_msgs::MoveArmResultConstPtr& result)
00257 {
00258 if( state.toString().compare("SUCCEEDED") == 0 )
00259 ROS_INFO("DarwinIcra12AlgNode::move_right_armDone: Goal Achieved!");
00260 else
00261 ROS_INFO("DarwinIcra12AlgNode::move_right_armDone: %s", state.toString().c_str());
00262
00263
00264 this->arm_moving=false;
00265 }
00266
00267 void DarwinIcra12AlgNode::move_right_armActive()
00268 {
00269
00270 }
00271
00272 void DarwinIcra12AlgNode::move_right_armFeedback(const arm_navigation_msgs::MoveArmFeedbackConstPtr& feedback)
00273 {
00274
00275
00276 bool feedback_is_ok = true;
00277
00278
00279
00280
00281
00282 if( !feedback_is_ok )
00283 {
00284 move_right_arm_client_.cancelGoal();
00285
00286 }
00287 }
00288 void DarwinIcra12AlgNode::move_jointsDone(const actionlib::SimpleClientGoalState& state, const control_msgs::FollowJointTrajectoryResultConstPtr& result)
00289 {
00290 if( state.toString().compare("SUCCEEDED") == 0 )
00291 ROS_INFO("DarwinIcra12AlgNode::move_jointsDone: Goal Achieved!");
00292 else
00293 ROS_INFO("DarwinIcra12AlgNode::move_jointsDone: %s", state.toString().c_str());
00294
00295
00296 this->joints_moving=false;
00297 }
00298
00299 void DarwinIcra12AlgNode::move_jointsActive()
00300 {
00301 ROS_INFO("DarwinIcra12AlgNode::move_jointsActive: Goal just went active!");
00302 }
00303
00304 void DarwinIcra12AlgNode::move_jointsFeedback(const control_msgs::FollowJointTrajectoryFeedbackConstPtr& feedback)
00305 {
00306 ROS_INFO("DarwinIcra12AlgNode::move_jointsFeedback: Got Feedback!");
00307
00308 bool feedback_is_ok = true;
00309
00310
00311
00312
00313
00314 if( !feedback_is_ok )
00315 {
00316 move_joints_client_.cancelGoal();
00317
00318 }
00319 }
00320
00321 void DarwinIcra12AlgNode::move_baseDone(const actionlib::SimpleClientGoalState& state, const move_base_msgs::MoveBaseResultConstPtr& result)
00322 {
00323 if( state.toString().compare("SUCCEEDED") == 0 )
00324 ROS_INFO("DarwinIcra12AlgNode::move_baseDone: Goal Achieved!");
00325 else
00326 ROS_INFO("DarwinIcra12AlgNode::move_baseDone: %s", state.toString().c_str());
00327
00328
00329 this->base_moving=false;
00330 }
00331
00332 void DarwinIcra12AlgNode::move_baseActive()
00333 {
00334
00335 }
00336
00337 void DarwinIcra12AlgNode::move_baseFeedback(const move_base_msgs::MoveBaseFeedbackConstPtr& feedback)
00338 {
00339
00340
00341 bool feedback_is_ok = true;
00342
00343
00344
00345
00346
00347 if( !feedback_is_ok )
00348 {
00349 move_base_client_.cancelGoal();
00350
00351 }
00352 }
00353
00354 void DarwinIcra12AlgNode::move_left_armDone(const actionlib::SimpleClientGoalState& state, const arm_navigation_msgs::MoveArmResultConstPtr& result)
00355 {
00356 if( state.toString().compare("SUCCEEDED") == 0 )
00357 ROS_INFO("DarwinIcra12AlgNode::move_armDone: Goal Achieved!");
00358 else
00359 ROS_INFO("DarwinIcra12AlgNode::move_armDone: %s", state.toString().c_str());
00360
00361
00362 this->arm_moving=false;
00363 }
00364
00365 void DarwinIcra12AlgNode::move_left_armActive()
00366 {
00367
00368 }
00369
00370 void DarwinIcra12AlgNode::move_left_armFeedback(const arm_navigation_msgs::MoveArmFeedbackConstPtr& feedback)
00371 {
00372
00373
00374 bool feedback_is_ok = true;
00375
00376
00377
00378
00379
00380 if( !feedback_is_ok )
00381 {
00382 move_left_arm_client_.cancelGoal();
00383
00384 }
00385 }
00386
00387
00388 void DarwinIcra12AlgNode::move_right_armMakeActionRequest()
00389 {
00390 ROS_INFO("DarwinIcra12AlgNode::move_right_armMakeActionRequest: Starting New Request!");
00391
00392
00393
00394 move_right_arm_client_.waitForServer();
00395 ROS_INFO("DarwinIcra12AlgNode::move_right_armMakeActionRequest: Server is Available!");
00396
00397
00398
00399 move_right_arm_client_.sendGoal(move_right_arm_goal_,
00400 boost::bind(&DarwinIcra12AlgNode::move_right_armDone, this, _1, _2),
00401 boost::bind(&DarwinIcra12AlgNode::move_right_armActive, this),
00402 boost::bind(&DarwinIcra12AlgNode::move_right_armFeedback, this, _1));
00403 ROS_INFO("DarwinIcra12AlgNode::move_right_armMakeActionRequest: Goal Sent. Wait for Result!");
00404 this->arm_moving=true;
00405 }
00406 void DarwinIcra12AlgNode::move_jointsMakeActionRequest()
00407 {
00408 ROS_INFO("DarwinIcra12AlgNode::move_jointsMakeActionRequest: Starting New Request!");
00409
00410
00411
00412 move_joints_client_.waitForServer();
00413 ROS_INFO("DarwinIcra12AlgNode::move_jointsMakeActionRequest: Server is Available!");
00414
00415
00416
00417 move_joints_client_.sendGoal(move_joints_goal_,
00418 boost::bind(&DarwinIcra12AlgNode::move_jointsDone, this, _1, _2),
00419 boost::bind(&DarwinIcra12AlgNode::move_jointsActive, this),
00420 boost::bind(&DarwinIcra12AlgNode::move_jointsFeedback, this, _1));
00421 ROS_INFO("DarwinIcra12AlgNode::move_jointsMakeActionRequest: Goal Sent. Wait for Result!");
00422 this->joints_moving=true;
00423 }
00424
00425 void DarwinIcra12AlgNode::move_baseMakeActionRequest()
00426 {
00427 ROS_INFO("DarwinIcra12AlgNode::move_baseMakeActionRequest: Starting New Request!");
00428
00429
00430
00431 move_base_client_.waitForServer();
00432 ROS_INFO("DarwinIcra12AlgNode::move_baseMakeActionRequest: Server is Available!");
00433
00434
00435
00436 move_base_client_.sendGoal(move_base_goal_,
00437 boost::bind(&DarwinIcra12AlgNode::move_baseDone, this, _1, _2),
00438 boost::bind(&DarwinIcra12AlgNode::move_baseActive, this),
00439 boost::bind(&DarwinIcra12AlgNode::move_baseFeedback, this, _1));
00440 ROS_INFO("DarwinIcra12AlgNode::move_baseMakeActionRequest: Goal Sent. Wait for Result!");
00441 this->base_moving=true;
00442 }
00443
00444 void DarwinIcra12AlgNode::move_left_armMakeActionRequest()
00445 {
00446 ROS_INFO("DarwinIcra12AlgNode::move_armMakeActionRequest: Starting New Request!");
00447
00448
00449
00450 move_left_arm_client_.waitForServer();
00451 ROS_INFO("DarwinIcra12AlgNode::move_armMakeActionRequest: Server is Available!");
00452
00453
00454
00455 move_left_arm_client_.sendGoal(move_left_arm_goal_,
00456 boost::bind(&DarwinIcra12AlgNode::move_left_armDone, this, _1, _2),
00457 boost::bind(&DarwinIcra12AlgNode::move_left_armActive, this),
00458 boost::bind(&DarwinIcra12AlgNode::move_left_armFeedback, this, _1));
00459 ROS_INFO("DarwinIcra12AlgNode::move_armMakeActionRequest: Goal Sent. Wait for Result!");
00460 this->arm_moving=true;
00461 }
00462
00463 void DarwinIcra12AlgNode::node_config_update(Config &config, uint32_t level)
00464 {
00465 this->alg_.lock();
00466
00467 this->alg_.unlock();
00468 }
00469
00470 void DarwinIcra12AlgNode::addNodeDiagnostics(void)
00471 {
00472 }
00473
00474
00475 int main(int argc,char *argv[])
00476 {
00477 return algorithm_base::main<DarwinIcra12AlgNode>(argc, argv, "darwin_icra12_alg_node");
00478 }