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
00036
00037 #include <math.h>
00038 #include <pluginlib/class_list_macros.h>
00039 #include "pr2_mechanism_model/robot.h"
00040 #include "pr2_mechanism_model/wrist_transmission.h"
00041
00042 using namespace pr2_mechanism_model;
00043 using namespace pr2_hardware_interface;
00044
00045 PLUGINLIB_DECLARE_CLASS(pr2_mechanism_model, WristTransmission,
00046 pr2_mechanism_model::WristTransmission,
00047 pr2_mechanism_model::Transmission)
00048
00049
00050 bool WristTransmission::initXml(TiXmlElement *elt, Robot *robot)
00051 {
00052 const char *name = elt->Attribute("name");
00053 name_ = name ? name : "";
00054
00055
00056 TiXmlElement *ael = elt->FirstChildElement("rightActuator");
00057 const char *actuator_name = ael ? ael->Attribute("name") : NULL;
00058 Actuator *a;
00059 if (!actuator_name || (a = robot->getActuator(actuator_name)) == NULL )
00060 {
00061 ROS_WARN("WristTransmission could not find actuator named \"%s\"", actuator_name);
00062 return false;
00063 }
00064 a->command_.enable_ = true;
00065 actuator_names_.push_back(actuator_name);
00066 const char *act_red = ael->Attribute("mechanicalReduction");
00067 if (!act_red)
00068 {
00069 ROS_WARN("WristTransmission's actuator \"%s\" was not given a reduction.", actuator_name);
00070 return false;
00071 }
00072 actuator_reduction_.push_back(atof(act_red));
00073
00074 ael = elt->FirstChildElement("leftActuator");
00075 actuator_name = ael ? ael->Attribute("name") : NULL;
00076 if (!actuator_name || (a = robot->getActuator(actuator_name)) == NULL )
00077 {
00078 ROS_WARN("WristTransmission could not find actuator named \"%s\"", actuator_name);
00079 return false;
00080 }
00081 a->command_.enable_ = true;
00082 actuator_names_.push_back(actuator_name);
00083 act_red = ael->Attribute("mechanicalReduction");
00084 if (!act_red)
00085 {
00086 ROS_WARN("WristTransmission's actuator \"%s\" was not given a reduction.", actuator_name);
00087 return false;
00088 }
00089 actuator_reduction_.push_back(atof(act_red));
00090
00091
00092 TiXmlElement *j = elt->FirstChildElement("flexJoint");
00093 const char *joint_name = j->Attribute("name");
00094 if (!joint_name)
00095 {
00096 ROS_ERROR("WristTransmission did not specify joint name");
00097 return false;
00098 }
00099 const boost::shared_ptr<const urdf::Joint> joint = robot->robot_model_.getJoint(joint_name);
00100
00101 if (!joint)
00102 {
00103 ROS_ERROR("WristTransmission could not find joint named \"%s\"", joint_name);
00104 return false;
00105 }
00106 joint_names_.push_back(joint_name);
00107 const char *joint_red = j->Attribute("mechanicalReduction");
00108 if (!joint_red)
00109 {
00110 ROS_WARN("WristTransmission's joint \"%s\" was not given a reduction.", joint_name);
00111 return false;
00112 }
00113 joint_reduction_.push_back(atof(joint_red));
00114
00115 j = elt->FirstChildElement("rollJoint");
00116 joint_name = j->Attribute("name");
00117 if (!joint_name)
00118 {
00119 ROS_ERROR("WristTransmission did not specify joint name");
00120 return false;
00121 }
00122 const boost::shared_ptr<const urdf::Joint> joint2 = robot->robot_model_.getJoint(joint_name);
00123
00124 if (!joint2)
00125 {
00126 ROS_ERROR("WristTransmission could not find joint named \"%s\"", joint_name);
00127 return false;
00128 }
00129 joint_names_.push_back(joint_name);
00130 joint_red = j->Attribute("mechanicalReduction");
00131 if (!joint_red)
00132 {
00133 ROS_WARN("WristTransmission's joint \"%s\" was not given a reduction.", joint_name);
00134 return false;
00135 }
00136 joint_reduction_.push_back(atof(joint_red));
00137
00138
00139 return true;
00140 }
00141
00142 bool WristTransmission::initXml(TiXmlElement *elt)
00143 {
00144 const char *name = elt->Attribute("name");
00145 name_ = name ? name : "";
00146
00147
00148 TiXmlElement *ael = elt->FirstChildElement("rightActuator");
00149 const char *actuator_name = ael ? ael->Attribute("name") : NULL;
00150 if (!actuator_name)
00151 {
00152 ROS_WARN("WristTransmission could not find actuator named \"%s\"", actuator_name);
00153 return false;
00154 }
00155 actuator_names_.push_back(actuator_name);
00156 const char *act_red = ael->Attribute("mechanicalReduction");
00157 if (!act_red)
00158 {
00159 ROS_WARN("WristTransmission's actuator \"%s\" was not given a reduction.", actuator_name);
00160 return false;
00161 }
00162 actuator_reduction_.push_back(atof(act_red));
00163
00164 ael = elt->FirstChildElement("leftActuator");
00165 actuator_name = ael ? ael->Attribute("name") : NULL;
00166 if (!actuator_name)
00167 {
00168 ROS_WARN("WristTransmission could not find actuator named \"%s\"", actuator_name);
00169 return false;
00170 }
00171 actuator_names_.push_back(actuator_name);
00172 act_red = ael->Attribute("mechanicalReduction");
00173 if (!act_red)
00174 {
00175 ROS_WARN("WristTransmission's actuator \"%s\" was not given a reduction.", actuator_name);
00176 return false;
00177 }
00178 actuator_reduction_.push_back(atof(act_red));
00179
00180
00181 TiXmlElement *j = elt->FirstChildElement("flexJoint");
00182 const char *joint_name = j->Attribute("name");
00183 if (!joint_name)
00184 {
00185 ROS_ERROR("WristTransmission did not specify joint name");
00186 return false;
00187 }
00188 joint_names_.push_back(joint_name);
00189 const char *joint_red = j->Attribute("mechanicalReduction");
00190 if (!joint_red)
00191 {
00192 ROS_WARN("WristTransmission's joint \"%s\" was not given a reduction.", joint_name);
00193 return false;
00194 }
00195 joint_reduction_.push_back(atof(joint_red));
00196
00197 j = elt->FirstChildElement("rollJoint");
00198 joint_name = j->Attribute("name");
00199 if (!joint_name)
00200 {
00201 ROS_ERROR("WristTransmission did not specify joint name");
00202 return false;
00203 }
00204 joint_names_.push_back(joint_name);
00205 joint_red = j->Attribute("mechanicalReduction");
00206 if (!joint_red)
00207 {
00208 ROS_WARN("WristTransmission's joint \"%s\" was not given a reduction.", joint_name);
00209 return false;
00210 }
00211 joint_reduction_.push_back(atof(joint_red));
00212
00213
00214 return true;
00215 }
00216
00217 void WristTransmission::propagatePosition(
00218 std::vector<Actuator*>& as, std::vector<JointState*>& js)
00219 {
00220 assert(as.size() == 2);
00221 assert(js.size() == 2);
00222
00223 js[0]->position_ = ((as[0]->state_.position_ / actuator_reduction_[0] - as[1]->state_.position_ / actuator_reduction_[1])/
00224 (2*joint_reduction_[0])) + js[0]->reference_position_;
00225 js[0]->velocity_ = (as[0]->state_.velocity_ / actuator_reduction_[0] - as[1]->state_.velocity_ / actuator_reduction_[1])/(2*joint_reduction_[0]);
00226 js[0]->measured_effort_ = joint_reduction_[0]*(as[0]->state_.last_measured_effort_ * actuator_reduction_[0] - as[1]->state_.last_measured_effort_ * actuator_reduction_[1]);
00227
00228 js[1]->position_ = ((-as[0]->state_.position_ / actuator_reduction_[0] - as[1]->state_.position_ / actuator_reduction_[1])/
00229 (2*joint_reduction_[1]))+js[1]->reference_position_;
00230 js[1]->velocity_ = (-as[0]->state_.velocity_ / actuator_reduction_[0] - as[1]->state_.velocity_ / actuator_reduction_[1])/(2*joint_reduction_[1]);
00231 js[1]->measured_effort_ = joint_reduction_[1]*(-as[0]->state_.last_measured_effort_ * actuator_reduction_[0] - as[1]->state_.last_measured_effort_ * actuator_reduction_[1]);
00232 }
00233
00234 void WristTransmission::propagatePositionBackwards(
00235 std::vector<JointState*>& js, std::vector<Actuator*>& as)
00236 {
00237 assert(as.size() == 2);
00238 assert(js.size() == 2);
00239
00240 as[0]->state_.position_ = (((js[0]->position_-js[0]->reference_position_)*joint_reduction_[0] -
00241 (js[1]->position_-js[1]->reference_position_)*joint_reduction_[1]) * actuator_reduction_[0]);
00242 as[0]->state_.velocity_ = ((js[0]->velocity_*joint_reduction_[0] - js[1]->velocity_*joint_reduction_[1]) * actuator_reduction_[0]);
00243 as[0]->state_.last_measured_effort_ = (js[0]->measured_effort_/joint_reduction_[0] - js[1]->measured_effort_/joint_reduction_[1]) /(2.0*actuator_reduction_[0]);
00244
00245 as[1]->state_.position_ = ((-(js[0]->position_-js[0]->reference_position_)*joint_reduction_[0] -
00246 (js[1]->position_-js[1]->reference_position_)*joint_reduction_[1]) * actuator_reduction_[1]);
00247 as[1]->state_.velocity_ = ((-js[0]->velocity_*joint_reduction_[0] - js[1]->velocity_*joint_reduction_[1]) * actuator_reduction_[1]);
00248 as[1]->state_.last_measured_effort_ = (-js[0]->measured_effort_/joint_reduction_[0] - js[1]->measured_effort_/joint_reduction_[1]) /(2.0*actuator_reduction_[1]);
00249
00250
00251 if (! simulated_actuator_timestamp_initialized_)
00252 {
00253
00254 as[0]->state_.sample_timestamp_ = ros::Duration(0);
00255 as[1]->state_.sample_timestamp_ = ros::Duration(0);
00256
00257
00258 if (ros::isStarted())
00259 {
00260 simulated_actuator_start_time_ = ros::Time::now();
00261 simulated_actuator_timestamp_initialized_ = true;
00262 }
00263 }
00264 else
00265 {
00266
00267 as[0]->state_.sample_timestamp_ = ros::Time::now() - simulated_actuator_start_time_;
00268 as[1]->state_.sample_timestamp_ = ros::Time::now() - simulated_actuator_start_time_;
00269 }
00270
00271 as[0]->state_.timestamp_ = as[0]->state_.sample_timestamp_.toSec();
00272 as[1]->state_.timestamp_ = as[1]->state_.sample_timestamp_.toSec();
00273
00274
00275
00276 this->joint_calibration_simulator_[0].simulateJointCalibration(js[0],as[1]);
00277 this->joint_calibration_simulator_[1].simulateJointCalibration(js[1],as[0]);
00278 }
00279
00280 void WristTransmission::propagateEffort(
00281 std::vector<JointState*>& js, std::vector<Actuator*>& as)
00282 {
00283 assert(as.size() == 2);
00284 assert(js.size() == 2);
00285
00286 as[0]->command_.enable_ = true;
00287 as[1]->command_.enable_ = true;
00288
00289 as[0]->command_.effort_ = (js[0]->commanded_effort_/joint_reduction_[0] - js[1]->commanded_effort_/joint_reduction_[1]) /(2.0*actuator_reduction_[0]);
00290 as[1]->command_.effort_ = (-js[0]->commanded_effort_/joint_reduction_[0] - js[1]->commanded_effort_/joint_reduction_[1]) /(2.0*actuator_reduction_[1]);
00291 }
00292
00293 void WristTransmission::propagateEffortBackwards(
00294 std::vector<Actuator*>& as, std::vector<JointState*>& js)
00295 {
00296 assert(as.size() == 2);
00297 assert(js.size() == 2);
00298
00299 js[0]->commanded_effort_ = joint_reduction_[0]*(as[0]->command_.effort_ * actuator_reduction_[0] - as[1]->command_.effort_ * actuator_reduction_[1]);
00300 js[1]->commanded_effort_ = joint_reduction_[1]*(-as[0]->command_.effort_ * actuator_reduction_[0] - as[1]->command_.effort_ * actuator_reduction_[1]);
00301 }
00302
00303
00304 void WristTransmission::setReductions(std::vector<double>& ar, std::vector<double>& jr)
00305 {
00306 actuator_reduction_ = ar;
00307 joint_reduction_ = jr;
00308 }
00309