00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #include <motoman_driver/industrial_robot_client/joint_trajectory_action.h>
00035 #include "motoman_driver/industrial_robot_client/motoman_utils.h"
00036 #include <industrial_robot_client/utils.h>
00037 #include <industrial_utils/param_utils.h>
00038 #include <industrial_utils/utils.h>
00039 #include <map>
00040 #include <string>
00041 #include <vector>
00042
00043 using industrial_robot_client::motoman_utils::getJointGroups;
00044
00045 namespace industrial_robot_client
00046 {
00047 namespace joint_trajectory_action
00048 {
00049
00050 const double JointTrajectoryAction::WATCHD0G_PERIOD_ = 1.0;
00051 const double JointTrajectoryAction::DEFAULT_GOAL_THRESHOLD_ = 0.01;
00052
00053 JointTrajectoryAction::JointTrajectoryAction() :
00054 action_server_(node_, "joint_trajectory_action",
00055 boost::bind(&JointTrajectoryAction::goalCB, this, _1),
00056 boost::bind(&JointTrajectoryAction::cancelCB, this, _1), false)
00057 {
00058 ros::NodeHandle pn("~");
00059
00060 pn.param("constraints/goal_threshold", goal_threshold_, DEFAULT_GOAL_THRESHOLD_);
00061
00062 std::map<int, RobotGroup> robot_groups;
00063 getJointGroups("topic_list", robot_groups);
00064
00065 for (int i = 0; i < robot_groups.size(); i++)
00066 {
00067
00068 std::string joint_path_action_name = robot_groups[i].get_ns() + "/" + robot_groups[i].get_name();
00069 std::vector<std::string> rg_joint_names = robot_groups[i].get_joint_names();
00070 int group_number_int = robot_groups[i].get_group_id();
00071
00072 all_joint_names_.insert(all_joint_names_.end(), rg_joint_names.begin(), rg_joint_names.end());
00073
00074 actionServer_ = new actionlib::ActionServer<control_msgs::FollowJointTrajectoryAction>(
00075 node_, joint_path_action_name + "/joint_trajectory_action" , false);
00076 actionServer_->registerGoalCallback(
00077 boost::bind(&JointTrajectoryAction::goalCB,
00078 this, _1, group_number_int));
00079 actionServer_->registerCancelCallback(
00080 boost::bind(&JointTrajectoryAction::cancelCB,
00081 this, _1, group_number_int));
00082
00083 pub_trajectory_command_ = node_.advertise<motoman_msgs::DynamicJointTrajectory>(
00084 joint_path_action_name + "/joint_path_command", 1);
00085 sub_trajectory_state_ = this->node_.subscribe<control_msgs::FollowJointTrajectoryFeedback>(
00086 joint_path_action_name + "/feedback_states", 1,
00087 boost::bind(&JointTrajectoryAction::controllerStateCB,
00088 this, _1, group_number_int));
00089 sub_robot_status_ = node_.subscribe(
00090 "robot_status", 1, &JointTrajectoryAction::robotStatusCB, this);
00091
00092 pub_trajectories_[group_number_int] = pub_trajectory_command_;
00093 sub_trajectories_[group_number_int] = (sub_trajectory_state_);
00094 sub_status_[group_number_int] = (sub_robot_status_);
00095
00096 this->act_servers_[group_number_int] = actionServer_;
00097
00098 this->act_servers_[group_number_int]->start();
00099
00100 this->watchdog_timer_map_[group_number_int] = node_.createTimer(
00101 ros::Duration(WATCHD0G_PERIOD_), boost::bind(
00102 &JointTrajectoryAction::watchdog, this, _1, group_number_int));
00103 }
00104
00105 pub_trajectory_command_ = node_.advertise<motoman_msgs::DynamicJointTrajectory>(
00106 "joint_path_command", 1);
00107
00108 this->robot_groups_ = robot_groups;
00109
00110 action_server_.start();
00111 }
00112
00113 JointTrajectoryAction::~JointTrajectoryAction()
00114 {
00115 }
00116
00117 void JointTrajectoryAction::robotStatusCB(
00118 const industrial_msgs::RobotStatusConstPtr &msg)
00119 {
00120 last_robot_status_ = msg;
00121 }
00122
00123 void JointTrajectoryAction::watchdog(const ros::TimerEvent &e)
00124 {
00125
00126 if (!last_trajectory_state_)
00127 {
00128 ROS_DEBUG("Waiting for subscription to joint trajectory state");
00129 }
00130 if (!trajectory_state_recvd_)
00131 {
00132 ROS_DEBUG("Trajectory state not received since last watchdog");
00133 }
00134
00135
00136 if (has_active_goal_)
00137 {
00138 if (!trajectory_state_recvd_)
00139 {
00140
00141 if (!last_trajectory_state_)
00142 {
00143 ROS_WARN("Aborting goal because we have never heard a controller state message.");
00144 }
00145 else
00146 {
00147 ROS_WARN_STREAM(
00148 "Aborting goal because we haven't heard from the controller in " << WATCHD0G_PERIOD_ << " seconds");
00149 }
00150 abortGoal();
00151 }
00152 }
00153
00154
00155 trajectory_state_recvd_ = false;
00156 }
00157
00158 void JointTrajectoryAction::watchdog(const ros::TimerEvent &e, int group_number)
00159 {
00160
00161 if (!last_trajectory_state_map_[group_number])
00162 {
00163 ROS_DEBUG("Waiting for subscription to joint trajectory state");
00164 }
00165 if (!trajectory_state_recvd_map_[group_number])
00166 {
00167 ROS_DEBUG("Trajectory state not received since last watchdog");
00168 }
00169
00170
00171 if (has_active_goal_map_[group_number])
00172 {
00173 if (!trajectory_state_recvd_map_[group_number])
00174 {
00175
00176 if (!last_trajectory_state_map_[group_number])
00177 {
00178 ROS_WARN("Aborting goal because we have never heard a controller state message.");
00179 }
00180 else
00181 {
00182 ROS_WARN_STREAM(
00183 "Aborting goal because we haven't heard from the controller in " << WATCHD0G_PERIOD_ << " seconds");
00184 }
00185 abortGoal(group_number);
00186 }
00187 }
00188
00189 trajectory_state_recvd_ = false;
00190 }
00191
00192 void JointTrajectoryAction::goalCB(JointTractoryActionServer::GoalHandle gh)
00193 {
00194 gh.setAccepted();
00195
00196 int group_number;
00197
00198
00199
00200 ros::Duration last_time_from_start(0.0);
00201
00202 motoman_msgs::DynamicJointTrajectory dyn_traj;
00203
00204 for (int i = 0; i < gh.getGoal()->trajectory.points.size(); i++)
00205 {
00206 motoman_msgs::DynamicJointPoint dpoint;
00207
00208 for (int rbt_idx = 0; rbt_idx < robot_groups_.size(); rbt_idx++)
00209 {
00210 size_t ros_idx = std::find(
00211 gh.getGoal()->trajectory.joint_names.begin(),
00212 gh.getGoal()->trajectory.joint_names.end(),
00213 robot_groups_[rbt_idx].get_joint_names()[0])
00214 - gh.getGoal()->trajectory.joint_names.begin();
00215
00216 bool is_found = ros_idx < gh.getGoal()->trajectory.joint_names.size();
00217
00218 group_number = rbt_idx;
00219 motoman_msgs::DynamicJointsGroup dyn_group;
00220
00221 int num_joints = robot_groups_[group_number].get_joint_names().size();
00222
00223 if (is_found)
00224 {
00225 if (gh.getGoal()->trajectory.points[i].positions.empty())
00226 {
00227 std::vector<double> positions(num_joints, 0.0);
00228 dyn_group.positions = positions;
00229 }
00230 else
00231 dyn_group.positions.insert(
00232 dyn_group.positions.begin(),
00233 gh.getGoal()->trajectory.points[i].positions.begin() + ros_idx,
00234 gh.getGoal()->trajectory.points[i].positions.begin() + ros_idx
00235 + robot_groups_[rbt_idx].get_joint_names().size());
00236
00237 if (gh.getGoal()->trajectory.points[i].velocities.empty())
00238 {
00239 std::vector<double> velocities(num_joints, 0.0);
00240 dyn_group.velocities = velocities;
00241 }
00242 else
00243 dyn_group.velocities.insert(
00244 dyn_group.velocities.begin(),
00245 gh.getGoal()->trajectory.points[i].velocities.begin()
00246 + ros_idx, gh.getGoal()->trajectory.points[i].velocities.begin()
00247 + ros_idx + robot_groups_[rbt_idx].get_joint_names().size());
00248
00249 if (gh.getGoal()->trajectory.points[i].accelerations.empty())
00250 {
00251 std::vector<double> accelerations(num_joints, 0.0);
00252 dyn_group.accelerations = accelerations;
00253 }
00254 else
00255 dyn_group.accelerations.insert(
00256 dyn_group.accelerations.begin(),
00257 gh.getGoal()->trajectory.points[i].accelerations.begin()
00258 + ros_idx, gh.getGoal()->trajectory.points[i].accelerations.begin()
00259 + ros_idx + robot_groups_[rbt_idx].get_joint_names().size());
00260 if (gh.getGoal()->trajectory.points[i].effort.empty())
00261 {
00262 std::vector<double> effort(num_joints, 0.0);
00263 dyn_group.effort = effort;
00264 }
00265 else
00266 dyn_group.effort.insert(
00267 dyn_group.effort.begin(),
00268 gh.getGoal()->trajectory.points[i].effort.begin()
00269 + ros_idx, gh.getGoal()->trajectory.points[i].effort.begin()
00270 + ros_idx + robot_groups_[rbt_idx].get_joint_names().size());
00271 dyn_group.time_from_start = gh.getGoal()->trajectory.points[i].time_from_start;
00272 dyn_group.group_number = group_number;
00273 dyn_group.num_joints = dyn_group.positions.size();
00274 }
00275
00276
00277 else
00278 {
00279 std::vector<double> positions(num_joints, 0.0);
00280 std::vector<double> velocities(num_joints, 0.0);
00281 std::vector<double> accelerations(num_joints, 0.0);
00282 std::vector<double> effort(num_joints, 0.0);
00283
00284 dyn_group.positions = positions;
00285 dyn_group.velocities = velocities;
00286 dyn_group.accelerations = accelerations;
00287 dyn_group.effort = effort;
00288
00289 dyn_group.time_from_start = gh.getGoal()->trajectory.points[i].time_from_start;
00290 dyn_group.group_number = group_number;
00291 dyn_group.num_joints = num_joints;
00292 }
00293
00294 dpoint.groups.push_back(dyn_group);
00295 }
00296 dpoint.num_groups = dpoint.groups.size();
00297 dyn_traj.points.push_back(dpoint);
00298 }
00299 dyn_traj.header = gh.getGoal()->trajectory.header;
00300 dyn_traj.header.stamp = ros::Time::now();
00301
00302 dyn_traj.joint_names = all_joint_names_;
00303
00304 this->pub_trajectory_command_.publish(dyn_traj);
00305 }
00306
00307 void JointTrajectoryAction::cancelCB(JointTractoryActionServer::GoalHandle gh)
00308 {
00309
00310
00311
00312 ROS_DEBUG("Received action cancel request");
00313 }
00314
00315 void JointTrajectoryAction::goalCB(JointTractoryActionServer::GoalHandle gh, int group_number)
00316 {
00317 if (!gh.getGoal()->trajectory.points.empty())
00318 {
00319 if (industrial_utils::isSimilar(
00320 this->robot_groups_[group_number].get_joint_names(),
00321 gh.getGoal()->trajectory.joint_names))
00322 {
00323
00324 if (has_active_goal_map_[group_number])
00325 {
00326 ROS_WARN("Received new goal, canceling current goal");
00327 abortGoal(group_number);
00328 }
00329
00330 if (withinGoalConstraints(last_trajectory_state_map_[group_number],
00331 gh.getGoal()->trajectory, group_number))
00332 {
00333 ROS_INFO_STREAM("Already within goal constraints, setting goal succeeded");
00334 gh.setAccepted();
00335 gh.setSucceeded();
00336 has_active_goal_map_[group_number] = false;
00337 }
00338 else
00339 {
00340 gh.setAccepted();
00341 active_goal_map_[group_number] = gh;
00342 has_active_goal_map_[group_number] = true;
00343
00344 ROS_INFO("Publishing trajectory");
00345
00346 current_traj_map_[group_number] = active_goal_map_[group_number].getGoal()->trajectory;
00347
00348 int num_joints = robot_groups_[group_number].get_joint_names().size();
00349
00350 motoman_msgs::DynamicJointTrajectory dyn_traj;
00351
00352 for (int i = 0; i < current_traj_map_[group_number].points.size(); ++i)
00353 {
00354 motoman_msgs::DynamicJointsGroup dyn_group;
00355 motoman_msgs::DynamicJointPoint dyn_point;
00356
00357 if (gh.getGoal()->trajectory.points[i].positions.empty())
00358 {
00359 std::vector<double> positions(num_joints, 0.0);
00360 dyn_group.positions = positions;
00361 }
00362 else
00363 dyn_group.positions = gh.getGoal()->trajectory.points[i].positions;
00364
00365 if (gh.getGoal()->trajectory.points[i].velocities.empty())
00366 {
00367 std::vector<double> velocities(num_joints, 0.0);
00368 dyn_group.velocities = velocities;
00369 }
00370 else
00371 dyn_group.velocities = gh.getGoal()->trajectory.points[i].velocities;
00372 if (gh.getGoal()->trajectory.points[i].accelerations.empty())
00373 {
00374 std::vector<double> accelerations(num_joints, 0.0);
00375 dyn_group.accelerations = accelerations;
00376 }
00377 else
00378 dyn_group.accelerations = gh.getGoal()->trajectory.points[i].accelerations;
00379 if (gh.getGoal()->trajectory.points[i].effort.empty())
00380 {
00381 std::vector<double> effort(num_joints, 0.0);
00382 dyn_group.effort = effort;
00383 }
00384 else
00385 dyn_group.effort = gh.getGoal()->trajectory.points[i].effort;
00386 dyn_group.time_from_start = gh.getGoal()->trajectory.points[i].time_from_start;
00387 dyn_group.group_number = group_number;
00388 dyn_group.num_joints = robot_groups_[group_number].get_joint_names().size();
00389 dyn_point.groups.push_back(dyn_group);
00390
00391 dyn_point.num_groups = 1;
00392 dyn_traj.points.push_back(dyn_point);
00393 }
00394 dyn_traj.header = gh.getGoal()->trajectory.header;
00395 dyn_traj.joint_names = gh.getGoal()->trajectory.joint_names;
00396 this->pub_trajectories_[group_number].publish(dyn_traj);
00397 }
00398 }
00399 else
00400 {
00401 ROS_ERROR("Joint trajectory action failing on invalid joints");
00402 control_msgs::FollowJointTrajectoryResult rslt;
00403 rslt.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
00404 gh.setRejected(rslt, "Joint names do not match");
00405 }
00406 }
00407 else
00408 {
00409 ROS_ERROR("Joint trajectory action failed on empty trajectory");
00410 control_msgs::FollowJointTrajectoryResult rslt;
00411 rslt.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_GOAL;
00412 gh.setRejected(rslt, "Empty trajectory");
00413 }
00414
00415
00416 if (gh.getGoal()->goal_time_tolerance.toSec() > 0.0)
00417 {
00418 ROS_WARN_STREAM("Ignoring goal time tolerance in action goal, may be supported in the future");
00419 }
00420 if (!gh.getGoal()->goal_tolerance.empty())
00421 {
00422 ROS_WARN_STREAM(
00423 "Ignoring goal tolerance in action, using paramater tolerance of " << goal_threshold_ << " instead");
00424 }
00425 if (!gh.getGoal()->path_tolerance.empty())
00426 {
00427 ROS_WARN_STREAM("Ignoring goal path tolerance, option not supported by ROS-Industrial drivers");
00428 }
00429 }
00430
00431 void JointTrajectoryAction::cancelCB(
00432 JointTractoryActionServer::GoalHandle gh, int group_number)
00433 {
00434 ROS_DEBUG("Received action cancel request");
00435 if (active_goal_map_[group_number] == gh)
00436 {
00437
00438 motoman_msgs::DynamicJointTrajectory empty;
00439 empty.joint_names = robot_groups_[group_number].get_joint_names();
00440 this->pub_trajectories_[group_number].publish(empty);
00441
00442
00443 active_goal_map_[group_number].setCanceled();
00444 has_active_goal_map_[group_number] = false;
00445 }
00446 else
00447 {
00448 ROS_WARN("Active goal and goal cancel do not match, ignoring cancel request");
00449 }
00450 }
00451
00452 void JointTrajectoryAction::controllerStateCB(
00453 const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg, int robot_id)
00454 {
00455 ROS_DEBUG("Checking controller state feedback");
00456 last_trajectory_state_map_[robot_id] = msg;
00457 trajectory_state_recvd_map_[robot_id] = true;
00458
00459 if (!has_active_goal_map_[robot_id])
00460 {
00461 ROS_DEBUG("No active goal, ignoring feedback");
00462 return;
00463 }
00464
00465 if (current_traj_map_[robot_id].points.empty())
00466 {
00467 ROS_DEBUG("Current trajectory is empty, ignoring feedback");
00468 return;
00469 }
00470
00471 if (!industrial_utils::isSimilar(robot_groups_[robot_id].get_joint_names(), msg->joint_names))
00472 {
00473 ROS_ERROR("Joint names from the controller don't match our joint names.");
00474 return;
00475 }
00476
00477
00478
00479
00480 ROS_DEBUG("Checking goal constraints");
00481 if (withinGoalConstraints(last_trajectory_state_map_[robot_id], current_traj_map_[robot_id], robot_id))
00482 {
00483 if (last_robot_status_)
00484 {
00485
00486
00487
00488
00489 if (last_robot_status_->in_motion.val == industrial_msgs::TriState::FALSE)
00490 {
00491 ROS_INFO("Inside goal constraints, stopped moving, return success for action");
00492 active_goal_map_[robot_id].setSucceeded();
00493 has_active_goal_map_[robot_id] = false;
00494 }
00495 else if (last_robot_status_->in_motion.val == industrial_msgs::TriState::UNKNOWN)
00496 {
00497 ROS_INFO("Inside goal constraints, return success for action");
00498 ROS_WARN("Robot status in motion unknown, the robot driver node and controller code should be updated");
00499 active_goal_map_[robot_id].setSucceeded();
00500 has_active_goal_map_[robot_id] = false;
00501 }
00502 else
00503 {
00504 ROS_DEBUG("Within goal constraints but robot is still moving");
00505 }
00506 }
00507 else
00508 {
00509 ROS_INFO("Inside goal constraints, return success for action");
00510 ROS_WARN("Robot status is not being published the robot driver node and controller code should be updated");
00511 active_goal_map_[robot_id].setSucceeded();
00512 has_active_goal_map_[robot_id] = false;
00513 }
00514 }
00515 }
00516
00517 void JointTrajectoryAction::controllerStateCB(
00518 const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg)
00519 {
00520 ROS_DEBUG("Checking controller state feedback");
00521 last_trajectory_state_ = msg;
00522 trajectory_state_recvd_ = true;
00523
00524 if (!has_active_goal_)
00525 {
00526 ROS_DEBUG("No active goal, ignoring feedback");
00527 return;
00528 }
00529 if (current_traj_.points.empty())
00530 {
00531 ROS_DEBUG("Current trajectory is empty, ignoring feedback");
00532 return;
00533 }
00534
00535 if (!industrial_utils::isSimilar(all_joint_names_, msg->joint_names))
00536 {
00537 ROS_ERROR("Joint names from the controller don't match our joint names.");
00538 return;
00539 }
00540
00541
00542
00543
00544 ROS_DEBUG("Checking goal constraints");
00545 if (withinGoalConstraints(last_trajectory_state_, current_traj_))
00546 {
00547 if (last_robot_status_)
00548 {
00549
00550
00551
00552
00553 if (last_robot_status_->in_motion.val == industrial_msgs::TriState::FALSE)
00554 {
00555 ROS_INFO("Inside goal constraints, stopped moving, return success for action");
00556 active_goal_.setSucceeded();
00557 has_active_goal_ = false;
00558 }
00559 else if (last_robot_status_->in_motion.val == industrial_msgs::TriState::UNKNOWN)
00560 {
00561 ROS_INFO("Inside goal constraints, return success for action");
00562 ROS_WARN("Robot status in motion unknown, the robot driver node and controller code should be updated");
00563 active_goal_.setSucceeded();
00564 has_active_goal_ = false;
00565 }
00566 else
00567 {
00568 ROS_DEBUG("Within goal constraints but robot is still moving");
00569 }
00570 }
00571 else
00572 {
00573 ROS_INFO("Inside goal constraints, return success for action");
00574 ROS_WARN("Robot status is not being published the robot driver node and controller code should be updated");
00575 active_goal_.setSucceeded();
00576 has_active_goal_ = false;
00577 }
00578 }
00579 }
00580
00581 void JointTrajectoryAction::abortGoal()
00582 {
00583
00584 trajectory_msgs::JointTrajectory empty;
00585 pub_trajectory_command_.publish(empty);
00586
00587
00588 active_goal_.setAborted();
00589 has_active_goal_ = false;
00590 }
00591
00592 void JointTrajectoryAction::abortGoal(int robot_id)
00593 {
00594
00595 motoman_msgs::DynamicJointTrajectory empty;
00596 pub_trajectories_[robot_id].publish(empty);
00597
00598
00599 active_goal_map_[robot_id].setAborted();
00600 has_active_goal_map_[robot_id] = false;
00601 }
00602
00603 bool JointTrajectoryAction::withinGoalConstraints(
00604 const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg,
00605 const trajectory_msgs::JointTrajectory & traj)
00606 {
00607 bool rtn = false;
00608 if (traj.points.empty())
00609 {
00610 ROS_WARN("Empty joint trajectory passed to check goal constraints, return false");
00611 rtn = false;
00612 }
00613 else
00614 {
00615 int last_point = traj.points.size() - 1;
00616
00617 if (industrial_robot_client::utils::isWithinRange(
00618 last_trajectory_state_->joint_names,
00619 last_trajectory_state_->actual.positions, traj.joint_names,
00620 traj.points[last_point].positions, goal_threshold_))
00621 {
00622 rtn = true;
00623 }
00624 else
00625 {
00626 rtn = false;
00627 }
00628 }
00629 return rtn;
00630 }
00631
00632 bool JointTrajectoryAction::withinGoalConstraints(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg,
00633 const motoman_msgs::DynamicJointTrajectory & traj)
00634 {
00635 bool rtn = false;
00636 if (traj.points.empty())
00637 {
00638 ROS_WARN("Empty joint trajectory passed to check goal constraints, return false");
00639 rtn = false;
00640 }
00641 else
00642 {
00643 int last_point = traj.points.size() - 1;
00644
00645 const motoman_msgs::DynamicJointsGroup &pt = traj.points[last_point].groups[3];
00646
00647 int group_number = pt.group_number;
00648
00649 if (industrial_robot_client::utils::isWithinRange(
00650 last_trajectory_state_map_[group_number]->joint_names,
00651 last_trajectory_state_map_[group_number]->actual.positions, traj.joint_names,
00652 traj.points[last_point].groups[3].positions, goal_threshold_))
00653 {
00654 rtn = true;
00655 }
00656 else
00657 {
00658 rtn = false;
00659 }
00660 }
00661 return rtn;
00662 }
00663
00664 bool JointTrajectoryAction::withinGoalConstraints(
00665 const control_msgs::FollowJointTrajectoryFeedbackConstPtr &msg,
00666 const trajectory_msgs::JointTrajectory & traj, int robot_id)
00667 {
00668 bool rtn = false;
00669 if (traj.points.empty())
00670 {
00671 ROS_WARN("Empty joint trajectory passed to check goal constraints, return false");
00672 rtn = false;
00673 }
00674 else
00675 {
00676 int last_point = traj.points.size() - 1;
00677
00678 int group_number = robot_id;
00679
00680 if (industrial_robot_client::utils::isWithinRange(
00681 robot_groups_[group_number].get_joint_names(),
00682 last_trajectory_state_map_[group_number]->actual.positions, traj.joint_names,
00683 traj.points[last_point].positions, goal_threshold_))
00684 {
00685 rtn = true;
00686 }
00687 else
00688 {
00689 rtn = false;
00690 }
00691 }
00692 return rtn;
00693 }
00694
00695 }
00696 }
00697
00698