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/simple_transmission.h"
00041
00042 using namespace pr2_mechanism_model;
00043 using namespace pr2_hardware_interface;
00044
00045 PLUGINLIB_DECLARE_CLASS(pr2_mechanism_model, SimpleTransmission,
00046 pr2_mechanism_model::SimpleTransmission,
00047 pr2_mechanism_model::Transmission)
00048
00049
00050 bool SimpleTransmission::initXml(TiXmlElement *elt, Robot *robot)
00051 {
00052 const char *name = elt->Attribute("name");
00053 name_ = name ? name : "";
00054
00055 TiXmlElement *jel = elt->FirstChildElement("joint");
00056 const char *joint_name = jel ? jel->Attribute("name") : NULL;
00057 if (!joint_name)
00058 {
00059 ROS_ERROR("SimpleTransmission did not specify joint name");
00060 return false;
00061 }
00062
00063 const boost::shared_ptr<const urdf::Joint> joint = robot->robot_model_.getJoint(joint_name);
00064 if (!joint)
00065 {
00066 ROS_ERROR("SimpleTransmission could not find joint named \"%s\"", joint_name);
00067 return false;
00068 }
00069 joint_names_.push_back(joint_name);
00070
00071 TiXmlElement *ael = elt->FirstChildElement("actuator");
00072 const char *actuator_name = ael ? ael->Attribute("name") : NULL;
00073 Actuator *a;
00074 if (!actuator_name || (a = robot->getActuator(actuator_name)) == NULL )
00075 {
00076 ROS_ERROR("SimpleTransmission could not find actuator named \"%s\"", actuator_name);
00077 return false;
00078 }
00079 a->command_.enable_ = true;
00080 actuator_names_.push_back(actuator_name);
00081
00082 mechanical_reduction_ = atof(elt->FirstChildElement("mechanicalReduction")->GetText());
00083
00084 return true;
00085 }
00086
00087 bool SimpleTransmission::initXml(TiXmlElement *elt)
00088 {
00089 const char *name = elt->Attribute("name");
00090 name_ = name ? name : "";
00091
00092 TiXmlElement *jel = elt->FirstChildElement("joint");
00093 const char *joint_name = jel ? jel->Attribute("name") : NULL;
00094 if (!joint_name)
00095 {
00096 ROS_ERROR("SimpleTransmission did not specify joint name");
00097 return false;
00098 }
00099 joint_names_.push_back(joint_name);
00100
00101 TiXmlElement *ael = elt->FirstChildElement("actuator");
00102 const char *actuator_name = ael ? ael->Attribute("name") : NULL;
00103 if (!actuator_name)
00104 {
00105 ROS_ERROR("SimpleTransmission could not find actuator named \"%s\"", actuator_name);
00106 return false;
00107 }
00108 actuator_names_.push_back(actuator_name);
00109
00110 mechanical_reduction_ = atof(elt->FirstChildElement("mechanicalReduction")->GetText());
00111
00112 return true;
00113 }
00114
00115 void SimpleTransmission::propagatePosition(
00116 std::vector<Actuator*>& as, std::vector<JointState*>& js)
00117 {
00118 assert(as.size() == 1);
00119 assert(js.size() == 1);
00120 js[0]->position_ = (as[0]->state_.position_ / mechanical_reduction_) + js[0]->reference_position_;
00121 js[0]->velocity_ = as[0]->state_.velocity_ / mechanical_reduction_;
00122 js[0]->measured_effort_ = as[0]->state_.last_measured_effort_ * mechanical_reduction_;
00123 }
00124
00125 void SimpleTransmission::propagatePositionBackwards(
00126 std::vector<JointState*>& js, std::vector<Actuator*>& as)
00127 {
00128 assert(as.size() == 1);
00129 assert(js.size() == 1);
00130 as[0]->state_.position_ = (js[0]->position_ - js[0]->reference_position_) * mechanical_reduction_;
00131 as[0]->state_.velocity_ = js[0]->velocity_ * mechanical_reduction_;
00132 as[0]->state_.last_measured_effort_ = js[0]->measured_effort_ / mechanical_reduction_;
00133
00134
00135 if (! simulated_actuator_timestamp_initialized_)
00136 {
00137
00138 as[0]->state_.sample_timestamp_ = ros::Duration(0);
00139
00140
00141 if (ros::isStarted())
00142 {
00143 simulated_actuator_start_time_ = ros::Time::now();
00144 simulated_actuator_timestamp_initialized_ = true;
00145 }
00146 }
00147 else
00148 {
00149
00150 as[0]->state_.sample_timestamp_ = ros::Time::now() - simulated_actuator_start_time_;
00151 }
00152
00153 as[0]->state_.timestamp_ = as[0]->state_.sample_timestamp_.toSec();
00154
00155
00156 this->joint_calibration_simulator_.simulateJointCalibration(js[0],as[0]);
00157 }
00158
00159 void SimpleTransmission::propagateEffort(
00160 std::vector<JointState*>& js, std::vector<Actuator*>& as)
00161 {
00162 assert(as.size() == 1);
00163 assert(js.size() == 1);
00164 as[0]->command_.enable_ = true;
00165 as[0]->command_.effort_ = js[0]->commanded_effort_ / mechanical_reduction_;
00166 }
00167
00168 void SimpleTransmission::propagateEffortBackwards(
00169 std::vector<Actuator*>& as, std::vector<JointState*>& js)
00170 {
00171 assert(as.size() == 1);
00172 assert(js.size() == 1);
00173 js[0]->commanded_effort_ = as[0]->command_.effort_ * mechanical_reduction_;
00174 }
00175