Go to the documentation of this file.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
00035 #include "joint_qualification_controllers/checkout_controller.h"
00036 #include "pluginlib/class_list_macros.h"
00037
00038 PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::CheckoutController,
00039 pr2_controller_interface::Controller)
00040
00041 using namespace std;
00042 using namespace joint_qualification_controllers;
00043
00044 CheckoutController::CheckoutController() :
00045 robot_(NULL),
00046 data_sent_(false),
00047 robot_data_pub_(NULL)
00048 {
00049 robot_data_.test_time = -1;
00050 robot_data_.num_joints = 0;
00051 robot_data_.num_actuators = 0;
00052
00053 state_ = STARTING;
00054 joint_count_ = 0;
00055 actuator_count_ = 0;
00056
00057 timeout_ = 30.0;
00058 }
00059
00060 bool CheckoutController::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
00061 {
00062 assert(robot);
00063 robot_ = robot;
00064
00065 joint_count_ = robot_->joint_states_.size();
00066 robot_data_.num_joints = joint_count_;
00067 robot_data_.timeout = false;
00068
00069 robot_data_.joint_data.resize(joint_count_);
00070
00071 for (int i = 0; i < joint_count_; i++)
00072 {
00073 pr2_mechanism_model::JointState *js = &(robot_->joint_states_[i]);
00074
00075 robot_data_.joint_data[i].index = i;
00076 robot_data_.joint_data[i].name = js->joint_->name;
00077 robot_data_.joint_data[i].is_cal = 0;
00078 robot_data_.joint_data[i].has_safety = js->joint_->safety && js->joint_->limits;
00079
00080
00081 switch (js->joint_->type)
00082 {
00083 case (urdf::Joint::FIXED):
00084 robot_data_.joint_data[i].type = "Fixed";
00085 break;
00086 case (urdf::Joint::REVOLUTE):
00087 robot_data_.joint_data[i].type = "Rotary";
00088 break;
00089 case (urdf::Joint::CONTINUOUS):
00090 robot_data_.joint_data[i].type = "Continuous";
00091 break;
00092 case (urdf::Joint::PRISMATIC):
00093 robot_data_.joint_data[i].type = "Prismatic";
00094 break;
00095 case (urdf::Joint::PLANAR):
00096 robot_data_.joint_data[i].type = "Planar";
00097 break;
00098 default:
00099 robot_data_.joint_data[i].type = "No type given!";
00100 break;
00101 }
00102 }
00103
00104
00105 actuator_count_ = robot_->model_->hw_->actuators_.size();
00106 robot_data_.num_actuators = actuator_count_;
00107 robot_data_.actuator_data.resize(actuator_count_);
00108
00109 pr2_hardware_interface::ActuatorMap::const_iterator it;
00110 int i = 0;
00111 for (it = robot_->model_->hw_->actuators_.begin();
00112 it != robot_->model_->hw_->actuators_.end();
00113 ++it, ++i)
00114 {
00115 pr2_hardware_interface::Actuator *actuator = it->second;
00116
00117 robot_data_.actuator_data[i].index = i;
00118 robot_data_.actuator_data[i].name = actuator->name_;
00119 robot_data_.actuator_data[i].id = actuator->state_.device_id_;
00120 }
00121
00122 n.param("timeout", timeout_, 30.0);
00123
00124 initial_time_ = robot_->getTime();
00125
00126 robot_data_pub_.reset(new realtime_tools::RealtimePublisher<joint_qualification_controllers::RobotData>(n, "/robot_checkout", 1, true));
00127
00128 return true;
00129 }
00130
00131 void CheckoutController::starting()
00132 {
00133 initial_time_ = robot_->getTime();
00134
00135 data_sent_ = false;
00136 }
00137
00138 void CheckoutController::update()
00139 {
00140 ros::Time time = robot_->getTime();
00141 bool cal = false;
00142
00143
00144
00145 if ((time - initial_time_).toSec() > timeout_ && state_ != ANALYZING && state_ != DONE)
00146 {
00147 analysis((time - initial_time_).toSec(), true);
00148 state_ = DONE;
00149 }
00150
00151 switch (state_)
00152 {
00153 case STARTING:
00154 initial_time_ = robot_->getTime();
00155 state_ = LISTENING;
00156 break;
00157 case LISTENING:
00158 {
00159 cal = true;
00160 for (int i = 0; i < joint_count_; ++i)
00161 {
00162
00163
00164 if (robot_->joint_states_[i].joint_->name.find("wheel_joint") != string::npos)
00165 continue;
00166
00167 if (robot_->joint_states_[i].joint_->type == urdf::Joint::FIXED)
00168 continue;
00169
00170 if (robot_->joint_states_[i].joint_->name.find("finger") != string::npos)
00171 continue;
00172 if (robot_->joint_states_[i].joint_->name.find("gripper_float_joint") != string::npos)
00173 continue;
00174 if (robot_->joint_states_[i].joint_->name.find("accelerometer_joint") != string::npos)
00175 continue;
00176 if (robot_->joint_states_[i].joint_->name.find("gripper_palm_joint") != string::npos)
00177 continue;
00178 if (robot_->joint_states_[i].joint_->name.find("gripper_tool_joint") != string::npos)
00179 continue;
00180
00181
00182
00183 if (robot_->joint_states_[i].joint_->name == "base_joint")
00184 continue;
00185
00186 if (!robot_->joint_states_[i].calibrated_)
00187 {
00188 cal = false;
00189 break;
00190 }
00191 }
00192
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205
00206
00207
00208
00209
00210
00211
00212 if (cal)
00213 state_ = ANALYZING;
00214
00215 break;
00216 }
00217 case ANALYZING:
00218 analysis((time - initial_time_).toSec());
00219 state_ = DONE;
00220 break;
00221 case DONE:
00222 if (!data_sent_)
00223 data_sent_ = sendData();
00224
00225
00226 break;
00227 }
00228
00229 }
00230
00231 bool CheckoutController::sendData()
00232 {
00233 if (robot_data_pub_->trylock())
00234 {
00235 joint_qualification_controllers::RobotData *out = &robot_data_pub_->msg_;
00236 out->test_time = robot_data_.test_time;
00237 out->num_joints = robot_data_.num_joints;
00238 out->num_actuators = robot_data_.num_actuators;
00239
00240 out->joint_data.resize(robot_data_.num_joints);
00241 out->actuator_data.resize(robot_data_.num_actuators);
00242
00243 for (int i = 0; i < joint_count_; i++)
00244 {
00245 out->joint_data[i].index = robot_data_.joint_data[i].index;
00246 out->joint_data[i].name = robot_data_.joint_data[i].name;
00247 out->joint_data[i].is_cal = robot_data_.joint_data[i].is_cal;
00248 out->joint_data[i].has_safety = robot_data_.joint_data[i].has_safety;
00249 out->joint_data[i].type = robot_data_.joint_data[i].type;
00250 }
00251
00252 for (int i = 0; i < actuator_count_; i++)
00253 {
00254 out->actuator_data[i].index = robot_data_.actuator_data[i].index;
00255 out->actuator_data[i].name = robot_data_.actuator_data[i].name;
00256 out->actuator_data[i].id = robot_data_.actuator_data[i].id;
00257 }
00258
00259 robot_data_pub_->unlockAndPublish();
00260
00261 return true;
00262 }
00263 return false;
00264 }
00265
00266 void CheckoutController::analysis(double time, bool timeout)
00267 {
00268 robot_data_.test_time = time;
00269 robot_data_.timeout = timeout;
00270
00271 for (int i = 0; i < joint_count_; i++)
00272 {
00273 robot_data_.joint_data[i].is_cal = robot_->joint_states_[i].calibrated_;
00274
00275 if (robot_->joint_states_[i].joint_->type == urdf::Joint::FIXED)
00276 robot_data_.joint_data[i].is_cal = true;
00277 }
00278
00279
00280
00281
00282
00283
00284
00285
00286
00287
00288
00289
00290
00291
00292
00293
00294 }